diff --git a/.gitattributes b/.gitattributes index 41a7367d84..efbe60f990 100644 --- a/.gitattributes +++ b/.gitattributes @@ -11,13 +11,4 @@ *.wav filter=lfs diff=lfs merge=lfs -text selfdrive/car/tests/test_models_segs.txt filter=lfs diff=lfs merge=lfs -text -system/hardware/tici/updater_weston filter=lfs diff=lfs merge=lfs -text -system/hardware/tici/updater_magic filter=lfs diff=lfs merge=lfs -text -third_party/**/*.a filter=lfs diff=lfs merge=lfs -text -third_party/**/*.so filter=lfs diff=lfs merge=lfs -text -third_party/**/*.so.* filter=lfs diff=lfs merge=lfs -text -third_party/**/*.dylib filter=lfs diff=lfs merge=lfs -text -third_party/acados/*/t_renderer filter=lfs diff=lfs merge=lfs -text -third_party/qt5/larch64/bin/lrelease filter=lfs diff=lfs merge=lfs -text -third_party/qt5/larch64/bin/lupdate filter=lfs diff=lfs merge=lfs -text -third_party/catch2/include/catch2/catch.hpp filter=lfs diff=lfs merge=lfs -text +system/hardware/tici/updater filter=lfs diff=lfs merge=lfs -text diff --git a/.github/ISSUE_TEMPLATE/enhancement.md b/.github/ISSUE_TEMPLATE/enhancement.md deleted file mode 100644 index 330b9b1101..0000000000 --- a/.github/ISSUE_TEMPLATE/enhancement.md +++ /dev/null @@ -1,8 +0,0 @@ ---- -name: Enhancement -about: For openpilot enhancement suggestions -title: '' -labels: 'enhancement' -assignees: '' ---- - diff --git a/.github/workflows/tests.yaml b/.github/workflows/tests.yaml index 834771d634..ee8f61f880 100644 --- a/.github/workflows/tests.yaml +++ b/.github/workflows/tests.yaml @@ -123,7 +123,7 @@ jobs: submodules: true - run: ./tools/op.sh setup - name: Build openpilot - run: scons -j$(nproc) + run: scons - name: Run unit tests timeout-minutes: ${{ contains(runner.name, 'nsc') && 2 || 999 }} run: | @@ -147,7 +147,7 @@ jobs: submodules: true - run: ./tools/op.sh setup - name: Build openpilot - run: scons -j$(nproc) + run: scons - name: Run replay timeout-minutes: ${{ contains(runner.name, 'nsc') && 2 || 20 }} continue-on-error: ${{ github.ref == 'refs/heads/master' }} @@ -179,7 +179,7 @@ jobs: repository: commaai/ci-artifacts ssh-key: ${{ secrets.CI_ARTIFACTS_DEPLOY_KEY }} path: ${{ github.workspace }}/ci-artifacts - - name: Push refs + - name: Prepare refs if: github.repository == 'commaai/openpilot' && github.ref == 'refs/heads/master' working-directory: ${{ github.workspace }}/ci-artifacts run: | @@ -191,7 +191,13 @@ jobs: echo "${{ github.sha }}" > ref_commit git add . git commit -m "process-replay refs for ${{ github.repository }}@${{ github.sha }}" || echo "No changes to commit" - git push origin process-replay --force + - name: Push refs + if: github.repository == 'commaai/openpilot' && github.ref == 'refs/heads/master' + uses: nick-fields/retry@7152eba30c6575329ac0576536151aca5a72780e + with: + timeout_minutes: 2 + max_attempts: 3 + command: cd ${{ github.workspace }}/ci-artifacts && git push origin process-replay --force - name: Run regen if: false timeout-minutes: 4 @@ -214,7 +220,7 @@ jobs: submodules: true - run: ./tools/op.sh setup - name: Build openpilot - run: scons -j$(nproc) + run: scons - name: Driving test timeout-minutes: 2 run: | @@ -235,7 +241,7 @@ jobs: submodules: true - run: ./tools/op.sh setup - name: Build openpilot - run: scons -j$(nproc) + run: scons - name: Create UI Report run: | source selfdrive/test/setup_xvfb.sh diff --git a/.gitignore b/.gitignore index ed49682f45..e4eaeb2c50 100644 --- a/.gitignore +++ b/.gitignore @@ -44,7 +44,7 @@ bin/ config.json compile_commands.json compare_runtime*.html -selfdrive/modeld/models/tg_compiled_flags.json +selfdrive/modeld/models/tg_input_devices.json # build artifacts docs_site/ diff --git a/.vscode/settings.json b/.vscode/settings.json index f0731c362d..811306f399 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -21,7 +21,6 @@ "common/**", "selfdrive/**", "system/**", - "third_party/**", "tools/**", ] } diff --git a/Jenkinsfile b/Jenkinsfile index 39175d89e3..a7f46ce17a 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -166,8 +166,8 @@ node { env.GIT_BRANCH = checkout(scm).GIT_BRANCH env.GIT_COMMIT = checkout(scm).GIT_COMMIT - def excludeBranches = ['__nightly', 'devel', 'devel-staging', 'release3', 'release3-staging', - 'release-tici', 'release-tizi', 'release-tizi-staging', 'release-mici-staging', 'testing-closet*', 'hotfix-*'] + def excludeBranches = ['__nightly', 'devel', 'devel-staging', + 'release-tizi', 'release-tizi-staging', 'release-mici', 'release-mici-staging', 'testing-closet*', 'hotfix-*'] def excludeRegex = excludeBranches.join('|').replaceAll('\\*', '.*') if (env.BRANCH_NAME != 'master' && !env.BRANCH_NAME.contains('__jenkins_loop_')) { @@ -179,7 +179,7 @@ node { try { if (env.BRANCH_NAME == 'devel-staging') { deviceStage("build release-tizi-staging", "tizi-needs-can", [], [ - step("build release-tizi-staging", "RELEASE_BRANCH=release-tizi-staging $SOURCE_DIR/release/build_release.sh && git push -f origin release-tizi-staging:release-mici-staging"), + step("build release-tizi-staging", "RELEASE_BRANCH=release-tizi-staging,release-mici-staging $SOURCE_DIR/release/build_release.sh"), ]) } @@ -247,7 +247,6 @@ node { step("test pandad loopback", "pytest selfdrive/pandad/tests/test_pandad_loopback.py"), step("test pandad spi", "pytest selfdrive/pandad/tests/test_pandad_spi.py"), step("test amp", "pytest system/hardware/tici/tests/test_amplifier.py"), - step("test qcomgpsd", "pytest system/qcomgpsd/tests/test_qcomgpsd.py", [diffPaths: ["system/qcomgpsd/"]]), ]) }, diff --git a/RELEASES.md b/RELEASES.md index 55141710d0..7946fce019 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,7 +1,13 @@ -Version 0.11.1 (2026-04-22) +Version 0.11.2 (2026-06-15) +======================== + + +Version 0.11.1 (2026-05-18) ======================== * New driver monitoring model * Improved image processing pipeline for driver camera +* Improved thermal policy for comma four +* Acura MDX 2022-24 support thanks to mvl-boston! * Rivian R1S and R1T 2025 support thanks to lukasloetkolben! Version 0.11.0 (2026-03-17) diff --git a/SConstruct b/SConstruct index 16c0752acf..5eb25ff50c 100644 --- a/SConstruct +++ b/SConstruct @@ -10,25 +10,28 @@ import numpy as np import SCons.Errors from SCons.Defaults import _stripixes +TICI = os.path.isfile('/TICI') + SCons.Warnings.warningAsException(True) Decider('MD5-timestamp') -SetOption('num_jobs', max(1, int(os.cpu_count()/2))) +SetOption('num_jobs', max(1, int(os.cpu_count()/(1 if "CI" in os.environ else 2)))) AddOption('--ccflags', action='store', type='string', default='', help='pass arbitrary flags over the command line') AddOption('--verbose', action='store_true', default=False, help='show full build commands') +release = not os.path.exists(File('#.gitattributes').abspath) # file absent on release branch, see release_files.py AddOption('--minimal', action='store_false', dest='extras', - default=os.path.exists(File('#.gitattributes').abspath), # minimal by default on release branch (where there's no LFS) + default=(not TICI and not release), help='the minimum build to run openpilot. no tests, tools, etc.') # Detect platform arch = subprocess.check_output(["uname", "-m"], encoding='utf8').rstrip() if platform.system() == "Darwin": arch = "Darwin" -elif arch == "aarch64" and os.path.isfile('/TICI'): +elif arch == "aarch64" and TICI: arch = "larch64" assert arch in [ "larch64", # linux tici arm64 @@ -37,8 +40,14 @@ assert arch in [ "Darwin", # macOS arm64 (x86 not supported) ] -pkg_names = ['bzip2', 'capnproto', 'eigen', 'ffmpeg', 'libjpeg', 'libyuv', 'ncurses', 'zeromq', 'zstd'] +pkg_names = ['acados', 'bzip2', 'capnproto', 'catch2', 'eigen', 'ffmpeg', 'json11', 'libjpeg', 'libyuv', 'ncurses', 'zeromq', 'zstd'] pkgs = [importlib.import_module(name) for name in pkg_names] +acados = pkgs[pkg_names.index('acados')] +acados_include_dirs = [ + acados.INCLUDE_DIR, + os.path.join(acados.INCLUDE_DIR, "blasfeo", "include"), + os.path.join(acados.INCLUDE_DIR, "hpipm", "include"), +] # ***** enforce a whitelist of system libraries ***** @@ -82,10 +91,10 @@ def _libflags(target, source, env, for_signature): env = Environment( ENV={ "PATH": os.environ['PATH'], - "PYTHONPATH": Dir("#").abspath + ':' + Dir(f"#third_party/acados").abspath, - "ACADOS_SOURCE_DIR": Dir("#third_party/acados").abspath, - "ACADOS_PYTHON_INTERFACE_PATH": Dir("#third_party/acados/acados_template").abspath, - "TERA_PATH": Dir("#").abspath + f"/third_party/acados/{arch}/t_renderer" + "PYTHONPATH": Dir("#").abspath, + "ACADOS_SOURCE_DIR": acados.DIR, + "ACADOS_PYTHON_INTERFACE_PATH": acados.TEMPLATE_DIR, + "TERA_PATH": acados.TERA_PATH }, CCFLAGS=[ "-g", @@ -105,22 +114,14 @@ env = Environment( CPPPATH=[ "#", "#msgq", - "#third_party", - "#third_party/json11", - "#third_party/linux/include", - "#third_party/acados/include", - "#third_party/acados/include/blasfeo/include", - "#third_party/acados/include/hpipm/include", - "#third_party/catch2/include", + acados_include_dirs, [x.INCLUDE_DIR for x in pkgs], ], LIBPATH=[ "#common", "#msgq_repo", - "#third_party", "#selfdrive/pandad", "#rednose/helpers", - f"#third_party/acados/{arch}/lib", [x.LIB_DIR for x in pkgs], ], RPATH=[], @@ -174,16 +175,6 @@ if not GetOption('verbose'): ): env[f"{action}COMSTR"] = f" [{short}] $TARGET" -# progress output -node_interval = 5 -node_count = 0 -def progress_function(node): - global node_count - node_count += node_interval - sys.stderr.write("progress: %d\n" % node_count) -if os.environ.get('SCONS_PROGRESS'): - Progress(progress_function, interval=node_interval) - # ********** Cython build environment ********** envCython = env.Clone() envCython["CPPPATH"] += [sysconfig.get_paths()['include'], np.get_include()] @@ -199,14 +190,24 @@ else: np_version = SCons.Script.Value(np.__version__) Export('envCython', 'np_version') -Export('env', 'arch') +Export('env', 'arch', 'acados') # Setup cache dir default_cache_dir = '/data/scons_cache' if arch == "larch64" else '/tmp/scons_cache' cache_dir = ARGUMENTS.get('cache_dir', default_cache_dir) +cache_size_limit = 4e9 if "CI" in os.environ else 2e9 CacheDir(cache_dir) Clean(["."], cache_dir) +def prune_cache_dir(target=None, source=None, env=None): + cache_files = sorted((os.path.join(root, f) for root, _, files in os.walk(cache_dir) for f in files), key=os.path.getmtime) + cache_size = sum(os.path.getsize(f) for f in cache_files) + for f in cache_files: + if cache_size < cache_size_limit: + break + cache_size -= os.path.getsize(f) + os.unlink(f) + # ********** start building stuff ********** # Build common module @@ -242,9 +243,6 @@ SConscript([ if arch == "larch64": SConscript(['system/camerad/SConscript']) -# Build openpilot -SConscript(['third_party/SConscript']) - # Build selfdrive SConscript([ 'selfdrive/pandad/SConscript', @@ -257,8 +255,8 @@ SConscript([ SConscript(['sunnypilot/SConscript']) -# Build tools -if arch != "larch64": +# Build desktop-only tools +if GetOption('extras') and arch != "larch64": SConscript([ 'tools/replay/SConscript', 'tools/cabana/SConscript', @@ -267,3 +265,37 @@ if arch != "larch64": env.CompilationDatabase('compile_commands.json') + +# progress output +def count_scons_nodes(nodes): + seen = set() + stack = list(nodes) + + while stack: + node = stack.pop().disambiguate() + if node in seen: + continue + seen.add(node) + executor = node.get_executor() + if executor is not None: + stack += executor.get_all_prerequisites() + executor.get_all_children() + + return len(seen) + +progress_interval = 5 +progress_count = 0 +progress_total = max(1, count_scons_nodes(env.arg2nodes(BUILD_TARGETS or [Dir('.')], env.fs.Entry))) + +def progress_function(node): + global progress_count + if progress_count >= progress_total: + return + progress_count = min(progress_count + progress_interval, progress_total) + progress = round(100. * progress_count / progress_total, 1) + sys.stderr.write("\rBuilding: %5.1f%%" % progress if sys.stderr.isatty() else "progress: %.1f\n" % progress) + if progress == 100. and sys.stderr.isatty(): + sys.stderr.write("\n") + sys.stderr.flush() + +Progress(progress_function, interval=progress_interval) +AddPostAction(BUILD_TARGETS or [Dir('.')], prune_cache_dir) diff --git a/cereal/log.capnp b/cereal/log.capnp index 9613950914..d2c7e2c896 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -273,11 +273,7 @@ struct GPSNMEAData { nmea @2 :Text; } -# android sensor_event_t struct SensorEventData { - version @0 :Int32; - sensor @1 :Int32; - type @2 :Int32; timestamp @3 :Int64; union { @@ -296,7 +292,10 @@ struct SensorEventData { struct SensorVec { v @0 :List(Float32); - status @1 :Int8; + + deprecated :group { + status @1 :Int8; + } } enum SensorSource { @@ -314,7 +313,11 @@ struct SensorEventData { mmc5603nj @11; } + # formerly based on android sensor_event_t deprecated :group { + version @0 :Int32; + sensor @1 :Int32; + type @2 :Int32; uncalibrated @10 :Bool; } } @@ -457,10 +460,10 @@ struct DeviceState @0xa4d8b5af2aa492eb { } enum ThermalStatus { - green @0; - yellow @1; - red @2; - danger @3; + ok @0; + warmDEPRECATED @1; + overheated @2; + critical @3; } enum NetworkType { @@ -2060,6 +2063,7 @@ struct DriverStateV2 { rightBlinkProb @8 :Float32; sunglassesProb @9 :Float32; phoneProb @13 :Float32; + sleepProb @14 :Float32; deprecated :group { notReadyProb @12 :List(Float32); @@ -2074,7 +2078,7 @@ struct DriverStateV2 { } } -struct DriverMonitoringState @0xb83cda094a1da284 { +struct DriverMonitoringStateDEPRECATED @0xb83cda094a1da284 { events @18 :List(OnroadEvent); faceDetected @1 :Bool; isDistracted @2 :Bool; @@ -2102,6 +2106,75 @@ struct DriverMonitoringState @0xb83cda094a1da284 { } } +struct DriverMonitoringState { + lockout @0 :Bool; + alertCountLockoutPercent @1 :Int8; + alertTimeLockoutPercent @2 :Int8; + + alwaysOn @3 :Bool; + alwaysOnLockout @4 :Bool; + + alertLevel @5 :AlertLevel; + activePolicy @6 :MonitoringPolicy; + isRHD @7 :Bool; + rhdCalibration @8 :CalibrationState; + + visionPolicyState @9 :VisionPolicyState; + wheeltouchPolicyState @10 :WheeltouchPolicyState; + + enum AlertLevel { + # ordinal must match the name to prevent bugs + # comparing against the raw ordinal value + none @0; + one @1; + two @2; + three @3; + } + + enum MonitoringPolicy { + wheeltouch @0; + vision @1; + } + + struct VisionPolicyState { + awarenessPercent @0 :Int8; + awarenessStep @1 :Float32; + isDistracted @2 :Bool; + distractedTypes @3 :DistractedTypes; + + faceDetected @4 :Bool; + pose @5 :Pose; + wheeltouchFallbackPercent @6 :Int8; + uncertainOffroadAlertPercent @7 :Int8; + + struct DistractedTypes { + pose @0: Bool; + eye @1: Bool; + phone @2: Bool; + } + + struct Pose { + pitch @0 :Float32; + yaw @1 :Float32; + pitchCalib @2 :CalibrationState; + yawCalib @3 :CalibrationState; + calibrated @4 :Bool; + uncertainty @5 :Float32; + } + } + + struct WheeltouchPolicyState { + awarenessPercent @0 :Int8; + awarenessStep @1 :Float32; + driverInteracting @2 :Bool; + } + + struct CalibrationState { + calibratedPercent @0 :Int8; + offset @1 :Float32; + } +} + struct Boot { wallTimeNanos @0 :UInt64; pstore @4 :Map(Text, Data); @@ -2227,7 +2300,8 @@ struct Sentinel { } struct UIDebug { - drawTimeMillis @0 :Float32; + cpuTimeMillis @0 :Float32; + frameTimeMillis @1 :Float32; } struct ManagerState { @@ -2375,7 +2449,6 @@ struct Event { boot @60 :Boot; # ********** openpilot daemon msgs ********** - gpsNMEA @3 :GPSNMEAData; can @5 :List(CanData); controlsState @7 :ControlsState; selfdriveState @130 :SelfdriveState; @@ -2400,7 +2473,6 @@ struct Event { qcomGnss @31 :QcomGnss; gpsLocationExternal @48 :GpsLocationData; gpsLocation @21 :GpsLocationData; - gnssMeasurements @91 :GnssMeasurements; liveParameters @61 :LiveParametersData; liveTorqueParameters @94 :LiveTorqueParametersData; liveDelay @146 : LiveDelayData; @@ -2408,7 +2480,7 @@ struct Event { thumbnail @66: Thumbnail; onroadEvents @134: List(OnroadEvent); carParams @69: Car.CarParams; - driverMonitoringState @71: DriverMonitoringState; + driverMonitoringState @151 :DriverMonitoringState; livePose @129 :LivePose; modelV2 @75 :ModelDataV2; drivingModelData @128 :DrivingModelData; @@ -2434,7 +2506,6 @@ struct Event { # systems stuff androidLog @20 :AndroidLogEntry; managerState @78 :ManagerState; - uploaderState @79 :UploaderState; procLog @33 :ProcLog; clocks @35 :Clocks; deviceState @6 :DeviceState; @@ -2444,12 +2515,6 @@ struct Event { # touch frame touch @135 :List(Touch); - # navigation - navInstruction @82 :NavInstruction; - navRoute @83 :NavRoute; - navThumbnail @84: Thumbnail; - mapRenderState @105: MapRenderState; - # UI services uiDebug @102 :UIDebug; @@ -2551,5 +2616,13 @@ struct Event { gyroscope2DEPRECATED @100 :SensorEventData; accelerometer2DEPRECATED @101 :SensorEventData; temperatureSensor2DEPRECATED @123 :SensorEventData; + driverMonitoringStateDEPRECATED @71 :DriverMonitoringStateDEPRECATED; + gpsNMEADEPRECATED @3 :GPSNMEAData; + uploaderStateDEPRECATED @79 :UploaderState; + navInstructionDEPRECATED @82 :NavInstruction; + navRouteDEPRECATED @83 :NavRoute; + navThumbnailDEPRECATED @84 :Thumbnail; + gnssMeasurementsDEPRECATED @91 :GnssMeasurements; + mapRenderStateDEPRECATED @105: MapRenderState; } } diff --git a/cereal/messaging/__init__.py b/cereal/messaging/__init__.py index 2c925b4cc4..ae32bfd4cb 100644 --- a/cereal/messaging/__init__.py +++ b/cereal/messaging/__init__.py @@ -259,11 +259,11 @@ class PubMaster: self.sock[s].send(dat) def wait_for_readers_to_update(self, s: str, timeout: int, dt: float = 0.05) -> bool: - for _ in range(int(timeout*(1./dt))): - if self.sock[s].all_readers_updated(): - return True - time.sleep(dt) - return False + try: + self.sock[s].wait_for_readers(timeout=timeout, interval=dt) + return True + except TimeoutError: + return False def all_readers_updated(self, s: str) -> bool: - return self.sock[s].all_readers_updated() # type: ignore + return self.sock[s].all_readers_updated() diff --git a/cereal/messaging/tests/test_messaging.py b/cereal/messaging/tests/test_messaging.py index afdab8a51f..97388446f4 100644 --- a/cereal/messaging/tests/test_messaging.py +++ b/cereal/messaging/tests/test_messaging.py @@ -30,7 +30,7 @@ def zmq_sleep(t=1): # TODO: this should take any capnp struct and returrn a msg with random populated data def random_carstate(): - fields = ["vEgo", "aEgo", "brake", "steeringAngleDeg"] + fields = ["vEgo", "aEgo", "steeringTorque", "steeringAngleDeg"] msg = messaging.new_message("carState") cs = msg.carState for f in fields: diff --git a/cereal/services.py b/cereal/services.py index 9d64f67f2f..f933fc0125 100755 --- a/cereal/services.py +++ b/cereal/services.py @@ -24,10 +24,7 @@ _services: dict[str, tuple] = { # note: the "EncodeIdx" packets will still be in the log "gyroscope": (True, 104., 104), "accelerometer": (True, 104., 104), - "magnetometer": (True, 25.), - "lightSensor": (True, 100., 100), "temperatureSensor": (True, 2., 200), - "gpsNMEA": (True, 9.), "deviceState": (True, 2., 1), "touch": (True, 20., 1), "can": (True, 100., 2053, QueueSize.BIG), # decimation gives ~3 msgs in a full segment @@ -56,7 +53,6 @@ _services: dict[str, tuple] = { "gpsLocation": (True, 1., 1), "ubloxGnss": (True, 10.), "qcomGnss": (True, 2.), - "gnssMeasurements": (True, 10., 10), "clocks": (True, 0.1, 1), "ubloxRaw": (True, 20.), "livePose": (True, 20., 4), @@ -75,10 +71,6 @@ _services: dict[str, tuple] = { "drivingModelData": (True, 20., 10), "modelV2": (True, 20., None, QueueSize.BIG), "managerState": (True, 2., 1), - "uploaderState": (True, 0., 1), - "navInstruction": (True, 1., 10), - "navRoute": (True, 0.), - "navThumbnail": (True, 0.), "qRoadEncodeIdx": (False, 20.), "userBookmark": (True, 0., 1), "soundPressure": (True, 10., 10), @@ -114,8 +106,6 @@ _services: dict[str, tuple] = { "livestreamRoadEncodeData": (False, 20., None, QueueSize.MEDIUM), "livestreamDriverEncodeData": (False, 20., None, QueueSize.MEDIUM), "customReservedRawData0": (True, 0.), - "customReservedRawData1": (True, 0.), - "customReservedRawData2": (True, 0.), } SERVICE_LIST = {name: Service(*vals) for idx, (name, vals) in enumerate(_services.items())} diff --git a/common/file_chunker.py b/common/file_chunker.py old mode 100644 new mode 100755 index ac9ddbb384..57dfc35531 --- a/common/file_chunker.py +++ b/common/file_chunker.py @@ -1,3 +1,5 @@ +#!/usr/bin/env python3 +import sys import math import os from pathlib import Path @@ -10,10 +12,13 @@ def get_chunk_name(name, idx, num_chunks): def get_manifest_path(name): return f"{name}.chunkmanifest" -def get_chunk_paths(path, file_size): - num_chunks = math.ceil(file_size / CHUNK_SIZE) +def _chunk_paths(path, num_chunks): return [get_manifest_path(path)] + [get_chunk_name(path, i, num_chunks) for i in range(num_chunks)] +def get_chunk_targets(path, file_size): + num_chunks = math.ceil(file_size / CHUNK_SIZE) + return _chunk_paths(path, num_chunks) + def chunk_file(path, targets): manifest_path, *chunk_paths = targets with open(path, 'rb') as f: @@ -26,6 +31,13 @@ def chunk_file(path, targets): Path(manifest_path).write_text(str(len(chunk_paths))) os.remove(path) +def get_existing_chunks(path): + if os.path.isfile(path): + return [path] + if os.path.isfile(manifest := get_manifest_path(path)): + num_chunks = int(Path(manifest).read_text().strip()) + return _chunk_paths(path, num_chunks) + raise FileNotFoundError(path) def read_file_chunked(path): manifest_path = get_manifest_path(path) @@ -35,3 +47,9 @@ def read_file_chunked(path): if os.path.isfile(path): return Path(path).read_bytes() raise FileNotFoundError(path) + + +if __name__ == "__main__": + path = sys.argv[1] + chunk_paths = get_chunk_targets(path, os.path.getsize(path)) + chunk_file(path, chunk_paths) diff --git a/common/parameterized.py b/common/parameterized.py index 7cd21bb9c5..f36d649dad 100644 --- a/common/parameterized.py +++ b/common/parameterized.py @@ -1,8 +1,13 @@ +import re import sys import pytest import inspect +def _to_safe_name(s): + return re.sub(r"[^a-zA-Z0-9_]+", "_", str(s)).strip("_") + + class parameterized: @staticmethod def expand(cases): @@ -34,7 +39,9 @@ def parameterized_class(attrs, input_list=None): def decorator(cls): globs = sys._getframe(1).f_globals for i, params in enumerate(params_list): - name = f"{cls.__name__}_{i}" + # append sanitized string param values so pytest -k can filter by them + suffix = "_".join(filter(None, (_to_safe_name(v) for v in params.values() if isinstance(v, str)))) + name = f"{cls.__name__}_{i}" + (f"_{suffix}" if suffix else "") new_cls = type(name, (cls,), dict(params)) new_cls.__module__ = cls.__module__ new_cls.__test__ = True # override inherited False so pytest collects this subclass diff --git a/common/params.py b/common/params.py index 494617200f..8af80c04bb 100644 --- a/common/params.py +++ b/common/params.py @@ -14,6 +14,6 @@ if __name__ == "__main__": if len(sys.argv) == 3: val = sys.argv[2] print(f"SET: {key} = {val}") - params.put(key, val) + params.put(key, val, block=True) elif len(sys.argv) == 2: print(f"GET: {key} = {params.get(key)}") diff --git a/common/params_keys.h b/common/params_keys.h index c92a6ed89c..5cb052ef0f 100644 --- a/common/params_keys.h +++ b/common/params_keys.h @@ -80,6 +80,7 @@ inline static std::unordered_map keys = { {"LiveDelay", {PERSISTENT | BACKUP, BYTES}}, {"LiveParameters", {PERSISTENT, JSON}}, {"LiveParametersV2", {PERSISTENT, BYTES}}, + {"LivestreamEncoderBitrate", {CLEAR_ON_MANAGER_START | DONT_LOG, INT}}, {"LiveTorqueParameters", {PERSISTENT | DONT_LOG, BYTES}}, {"LocationFilterInitialState", {PERSISTENT, BYTES}}, {"LateralManeuverMode", {CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION, BOOL}}, @@ -103,8 +104,6 @@ inline static std::unordered_map keys = { {"OnroadCycleRequested", {CLEAR_ON_MANAGER_START, BOOL}}, {"OpenpilotEnabledToggle", {PERSISTENT | BACKUP, BOOL, "1"}}, {"PandaHeartbeatLost", {CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION, BOOL}}, - {"PandaSomResetTriggered", {CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION, BOOL}}, - {"PandaSignatures", {CLEAR_ON_MANAGER_START, BYTES}}, {"PrimeType", {PERSISTENT, INT}}, {"RecordAudio", {PERSISTENT | BACKUP, BOOL}}, {"RecordAudioFeedback", {PERSISTENT | BACKUP, BOOL, "0"}}, @@ -132,6 +131,8 @@ inline static std::unordered_map keys = { {"UpdaterLastFetchTime", {PERSISTENT, TIME}}, {"UptimeOffroad", {PERSISTENT, FLOAT, "0.0"}}, {"UptimeOnroad", {PERSISTENT, FLOAT, "0.0"}}, + {"UsbGpuPresent", {CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION, BOOL}}, + {"UsbGpuCompiled", {CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION, BOOL}}, {"Version", {PERSISTENT, STRING}}, // --- sunnypilot params --- // diff --git a/common/params_pyx.pyx b/common/params_pyx.pyx index bffa89b5d3..9a952f6ebe 100644 --- a/common/params_pyx.pyx +++ b/common/params_pyx.pyx @@ -142,33 +142,28 @@ cdef class Params: cdef ParamKeyType t = self.p.getKeyType(k) return ensure_bytes(self.python2cpp(type(dat), t, dat, key)) - def put(self, key, dat): + def put(self, key, dat, bool block = False): """ - Warning: This function blocks until the param is written to disk! + Warning: block=True blocks until the param is written to disk! In very rare cases this can take over a second, and your code will hang. - Use the put_nonblocking, put_bool_nonblocking in time sensitive code, but - in general try to avoid writing params as much as possible. + Use block=False in time sensitive code, but in general try to avoid + writing params as much as possible. """ cdef string k = self.check_key(key) cdef string dat_bytes = self._put_cast(key, dat) with nogil: - self.p.put(k, dat_bytes) + if block: + self.p.put(k, dat_bytes) + else: + self.p.putNonBlocking(k, dat_bytes) - def put_bool(self, key, bool val): + def put_bool(self, key, bool val, bool block = False): cdef string k = self.check_key(key) with nogil: - self.p.putBool(k, val) - - def put_nonblocking(self, key, dat): - cdef string k = self.check_key(key) - cdef string dat_bytes = self._put_cast(key, dat) - with nogil: - self.p.putNonBlocking(k, dat_bytes) - - def put_bool_nonblocking(self, key, bool val): - cdef string k = self.check_key(key) - with nogil: - self.p.putBoolNonBlocking(k, val) + if block: + self.p.putBool(k, val) + else: + self.p.putBoolNonBlocking(k, val) def remove(self, key): cdef string k = self.check_key(key) diff --git a/common/realtime.py b/common/realtime.py index 0b14681021..91d2e165e9 100644 --- a/common/realtime.py +++ b/common/realtime.py @@ -28,6 +28,11 @@ class Priority: CTRL_HIGH = 53 +def drop_realtime() -> None: + if sys.platform == 'linux' and not PC: + os.sched_setscheduler(0, os.SCHED_OTHER, os.sched_param(0)) + + def set_core_affinity(cores: list[int]) -> None: if sys.platform == 'linux' and not PC: os.sched_setaffinity(0, cores) diff --git a/common/swaglog.cc b/common/swaglog.cc index d73f0c1a59..8811d61d8f 100644 --- a/common/swaglog.cc +++ b/common/swaglog.cc @@ -11,7 +11,7 @@ #include #include -#include "third_party/json11/json11.hpp" +#include "json11/json11.hpp" #include "common/version.h" #include "system/hardware/hw.h" diff --git a/common/tests/test_params.py b/common/tests/test_params.py index 592bf2c4b2..fcb8e5a185 100644 --- a/common/tests/test_params.py +++ b/common/tests/test_params.py @@ -12,17 +12,17 @@ class TestParams: self.params = Params() def test_params_put_and_get(self): - self.params.put("DongleId", "cb38263377b873ee") + self.params.put("DongleId", "cb38263377b873ee", block=True) assert self.params.get("DongleId") == "cb38263377b873ee" def test_params_non_ascii(self): st = b"\xe1\x90\xff" - self.params.put("CarParams", st) + self.params.put("CarParams", st, block=True) assert self.params.get("CarParams") == st def test_params_get_cleared_manager_start(self): - self.params.put("CarParams", b"test") - self.params.put("DongleId", "cb38263377b873ee") + self.params.put("CarParams", b"test", block=True) + self.params.put("DongleId", "cb38263377b873ee", block=True) assert self.params.get("CarParams") == b"test" undefined_param = self.params.get_param_path(uuid.uuid4().hex) @@ -36,15 +36,15 @@ class TestParams: assert not os.path.isfile(undefined_param) def test_params_two_things(self): - self.params.put("DongleId", "bob") - self.params.put("AthenadPid", 123) + self.params.put("DongleId", "bob", block=True) + self.params.put("AthenadPid", 123, block=True) assert self.params.get("DongleId") == "bob" assert self.params.get("AthenadPid") == 123 def test_params_get_block(self): def _delayed_writer(): time.sleep(0.1) - self.params.put("CarParams", b"test") + self.params.put("CarParams", b"test", block=True) threading.Thread(target=_delayed_writer).start() assert self.params.get("CarParams") is None assert self.params.get("CarParams", block=True) == b"test" @@ -57,10 +57,10 @@ class TestParams: self.params.get_bool("swag") with pytest.raises(UnknownKeyName): - self.params.put("swag", "abc") + self.params.put("swag", "abc", block=True) with pytest.raises(UnknownKeyName): - self.params.put_bool("swag", True) + self.params.put_bool("swag", True, block=True) def test_remove_not_there(self): assert self.params.get("CarParams") is None @@ -71,23 +71,23 @@ class TestParams: self.params.remove("IsMetric") assert not self.params.get_bool("IsMetric") - self.params.put_bool("IsMetric", True) + self.params.put_bool("IsMetric", True, block=True) assert self.params.get_bool("IsMetric") - self.params.put_bool("IsMetric", False) + self.params.put_bool("IsMetric", False, block=True) assert not self.params.get_bool("IsMetric") - self.params.put("IsMetric", True) + self.params.put("IsMetric", True, block=True) assert self.params.get_bool("IsMetric") - self.params.put("IsMetric", False) + self.params.put("IsMetric", False, block=True) assert not self.params.get_bool("IsMetric") def test_put_non_blocking_with_get_block(self): q = Params() def _delayed_writer(): time.sleep(0.1) - Params().put_nonblocking("CarParams", b"test") + Params().put("CarParams", b"test") threading.Thread(target=_delayed_writer).start() assert q.get("CarParams") is None assert q.get("CarParams", True) == b"test" @@ -96,7 +96,7 @@ class TestParams: q = Params() def _delayed_writer(): time.sleep(0.1) - Params().put_bool_nonblocking("CarParams", True) + Params().put_bool("CarParams", True) threading.Thread(target=_delayed_writer).start() assert q.get("CarParams") is None assert q.get("CarParams", True) == b"1" @@ -123,19 +123,19 @@ class TestParams: def test_params_get_type(self): # json - self.params.put("ApiCache_FirehoseStats", {"a": 0}) + self.params.put("ApiCache_FirehoseStats", {"a": 0}, block=True) assert self.params.get("ApiCache_FirehoseStats") == {"a": 0} # int - self.params.put("BootCount", 1441) + self.params.put("BootCount", 1441, block=True) assert self.params.get("BootCount") == 1441 # bool - self.params.put("AdbEnabled", True) + self.params.put("AdbEnabled", True, block=True) assert self.params.get("AdbEnabled") assert isinstance(self.params.get("AdbEnabled"), bool) # time now = datetime.datetime.now(datetime.UTC) - self.params.put("InstallDate", now) + self.params.put("InstallDate", now, block=True) assert self.params.get("InstallDate") == now diff --git a/common/tests/test_swaglog.cc b/common/tests/test_swaglog.cc index c97f907c24..26fd33436b 100644 --- a/common/tests/test_swaglog.cc +++ b/common/tests/test_swaglog.cc @@ -7,7 +7,7 @@ #include "common/util.h" #include "common/version.h" #include "system/hardware/hw.h" -#include "third_party/json11/json11.hpp" +#include "json11/json11.hpp" #include "sunnypilot/common/version.h" diff --git a/common/utils.py b/common/utils.py index 28b9274d82..183363f39d 100644 --- a/common/utils.py +++ b/common/utils.py @@ -48,7 +48,7 @@ def sudo_write(val: str, path: str) -> None: def sudo_read(path: str) -> str: try: - return subprocess.check_output(f"sudo cat {path}", shell=True, encoding='utf8').strip() + return subprocess.check_output(["sudo", "cat", "--", path], encoding='utf8').strip() except Exception: return "" diff --git a/common/version.h b/common/version.h index 41440556c5..5a09588e22 100644 --- a/common/version.h +++ b/common/version.h @@ -1 +1 @@ -#define COMMA_VERSION "0.11.1" +#define COMMA_VERSION "0.11.2" diff --git a/conftest.py b/conftest.py index 2f2db08d5d..de37572317 100644 --- a/conftest.py +++ b/conftest.py @@ -7,25 +7,19 @@ from openpilot.common.prefix import OpenpilotPrefix from openpilot.system.manager import manager from openpilot.system.hardware import TICI, HARDWARE -# TODO: pytest-cpp doesn't support FAIL, and we need to create test translations in sessionstart -# pending https://github.com/pytest-dev/pytest-cpp/pull/147 +# these are heavy CI-only tests, invoked explicitly in .github/workflows/tests.yaml collect_ignore = [ "selfdrive/test/process_replay/test_processes.py", "selfdrive/test/process_replay/test_regen.py", + # tinygrad JIT has process-global state. Other test files import modeld → tinygrad, + # which corrupts JIT captures for test_warp.py in the same process. Run separately in CI. + "sunnypilot/modeld_v2/tests/test_warp.py", ] collect_ignore_glob = [ "selfdrive/debug/*.py", - "selfdrive/modeld/*.py", - "sunnypilot/modeld*/*.py", ] -def pytest_sessionstart(session): - # TODO: fix tests and enable test order randomization - if session.config.pluginmanager.hasplugin('randomly'): - session.config.option.randomly_reorganize = False - - @pytest.hookimpl(hookwrapper=True, trylast=True) def pytest_runtest_call(item): # ensure we run as a hook after capturemanager's @@ -97,15 +91,3 @@ def pytest_collection_modifyitems(config, items): class_property_name = item.get_closest_marker('xdist_group_class_property').args[0] class_property_value = getattr(item.cls, class_property_name) item.add_marker(pytest.mark.xdist_group(class_property_value)) - - -@pytest.hookimpl(trylast=True) -def pytest_configure(config): - config_line = "xdist_group_class_property: group tests by a property of the class that contains them" - config.addinivalue_line("markers", config_line) - - config_line = "nocapture: don't capture test output" - config.addinivalue_line("markers", config_line) - - config_line = "shared_download_cache: share download cache between tests" - config.addinivalue_line("markers", config_line) diff --git a/docs/SAFETY.md b/docs/SAFETY.md index 25815e3372..0a662ac6cd 100644 --- a/docs/SAFETY.md +++ b/docs/SAFETY.md @@ -4,8 +4,8 @@ openpilot is an Adaptive Cruise Control (ACC) and Automated Lane Centering (ALC) Like other ACC and ALC systems, openpilot is a failsafe passive system and it requires the driver to be alert and to pay attention at all times. -In order to enforce driver alertness, openpilot includes a driver monitoring feature -that alerts the driver when distracted. +To assist the driver in maintaining alertness, openpilot includes a driver monitoring feature +that alerts when it detects driver distraction. However, even with an attentive driver, we must make further efforts for the system to be safe. We repeat, **driver alertness is necessary, but not sufficient, for openpilot to be diff --git a/docs/ext/glossary.py b/docs/ext/glossary.py index 35c92add10..9bbf3c78d7 100644 --- a/docs/ext/glossary.py +++ b/docs/ext/glossary.py @@ -8,7 +8,7 @@ from markdown.extensions import Extension from markdown.preprocessors import Preprocessor from markdown.treeprocessors import Treeprocessor -from zensical.extensions.links import LinksProcessor +from zensical.extensions.links import LinksTreeprocessor GlossaryTerm = tuple[str, re.Pattern[str], str] @@ -78,7 +78,7 @@ class GlossaryTreeprocessor(Treeprocessor): def run(self, root: ET.Element) -> None: at = self.md.treeprocessors.get_index_for_name("zrelpath") processor = self.md.treeprocessors[at] - if not isinstance(processor, LinksProcessor): + if not isinstance(processor, LinksTreeprocessor): raise TypeError("Links processor not registered") if processor.path == GLOSSARY_PAGE: return diff --git a/docs/how-to/turn-the-speed-blue.md b/docs/how-to/turn-the-speed-blue.md index bc1d634012..b5692daff7 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 -j$(nproc) +scons ``` ## 2. Run replay diff --git a/launch_env.sh b/launch_env.sh index e409a80dd4..d71a5c2767 100755 --- a/launch_env.sh +++ b/launch_env.sh @@ -16,7 +16,7 @@ export VECLIB_MAXIMUM_THREADS=1 export QCOM_PRIORITY=12 if [ -z "$AGNOS_VERSION" ]; then - export AGNOS_VERSION="17.2" + export AGNOS_VERSION="18.4" fi export STAGING_ROOT="/data/safe_staging" diff --git a/msgq_repo b/msgq_repo index b7688b9bd7..9beb84af67 160000 --- a/msgq_repo +++ b/msgq_repo @@ -1 +1 @@ -Subproject commit b7688b9bd731dea4520adf248bf1eb49b6dde776 +Subproject commit 9beb84af67527f7b6bfee349dcbe3dbb8d4f4789 diff --git a/opendbc_repo b/opendbc_repo index 4dad7b09dd..10e654bf21 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit 4dad7b09dda58ac161988b7949355f7300a3b0f2 +Subproject commit 10e654bf216233e72660c7906574d66ed75b1a16 diff --git a/openpilot/third_party b/openpilot/third_party deleted file mode 120000 index d838c05a86..0000000000 --- a/openpilot/third_party +++ /dev/null @@ -1 +0,0 @@ -../third_party \ No newline at end of file diff --git a/panda b/panda index 0a9ef7ab54..d994e8e800 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 0a9ef7ab54224e0df79a77448eda67023b285406 +Subproject commit d994e8e8009d934a94c3a94c863b559118353bdd diff --git a/pyproject.toml b/pyproject.toml index fd72c128fc..8b995a3a7b 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -20,14 +20,17 @@ dependencies = [ # core "cffi", "scons", - "pycapnp", + "pycapnp==2.1.0", # 2.2 introduces a memory leak due to cyclic references "Cython", "setuptools", "numpy >=2.0", # vendored native dependencies "bzip2 @ git+https://github.com/commaai/dependencies.git@release-bzip2#subdirectory=bzip2", + "bootstrap-icons @ git+https://github.com/commaai/dependencies.git@release-bootstrap-icons#subdirectory=bootstrap-icons", "capnproto @ git+https://github.com/commaai/dependencies.git@release-capnproto#subdirectory=capnproto", + "catch2 @ git+https://github.com/commaai/dependencies.git@release-catch2#subdirectory=catch2", + "acados @ git+https://github.com/commaai/dependencies.git@release-acados#subdirectory=acados", "eigen @ git+https://github.com/commaai/dependencies.git@release-eigen#subdirectory=eigen", "ffmpeg @ git+https://github.com/commaai/dependencies.git@release-ffmpeg#subdirectory=ffmpeg", "libjpeg @ git+https://github.com/commaai/dependencies.git@release-libjpeg#subdirectory=libjpeg", @@ -36,8 +39,10 @@ dependencies = [ "ncurses @ git+https://github.com/commaai/dependencies.git@release-ncurses#subdirectory=ncurses", "zeromq @ git+https://github.com/commaai/dependencies.git@release-zeromq#subdirectory=zeromq", "libusb @ git+https://github.com/commaai/dependencies.git@release-libusb#subdirectory=libusb", + "json11 @ git+https://github.com/commaai/dependencies.git@release-json11#subdirectory=json11", "git-lfs @ git+https://github.com/commaai/dependencies.git@release-git-lfs#subdirectory=git-lfs", "gcc-arm-none-eabi @ git+https://github.com/commaai/dependencies.git@release-gcc-arm-none-eabi#subdirectory=gcc-arm-none-eabi", + "xvfb @ git+https://github.com/commaai/dependencies.git@release-xvfb#subdirectory=xvfb", # body / webrtcd "av", @@ -58,9 +63,6 @@ dependencies = [ "json-rpc", "websocket_client", - # acados deps - "casadi >=3.6.6", # 3.12 fixed in 3.6.6 - # joystickd "inputs", @@ -73,7 +75,7 @@ dependencies = [ "zstandard", # ui - "raylib > 5.5.0.3", + "raylib @ git+https://github.com/commaai/dependencies.git@release-raylib#subdirectory=raylib", "qrcode", "jeepney", "pillow", @@ -94,7 +96,6 @@ testing = [ "pytest-subtests", # https://github.com/pytest-dev/pytest-xdist/pull/1229 "pytest-xdist @ git+https://github.com/sshane/pytest-xdist@2b4372bd62699fb412c4fe2f95bf9f01bd2018da", - "pytest-asyncio", "pytest-mock", "ruff", "codespell", @@ -107,7 +108,7 @@ dev = [ ] tools = [ - "imgui @ git+https://github.com/commaai/dependencies.git@release-imgui#subdirectory=imgui", + "imgui @ git+https://github.com/commaai/dependencies.git@release-imgui#subdirectory=imgui", "metadrive-simulator @ git+https://github.com/commaai/metadrive.git@minimal ; (platform_machine != 'aarch64')", ] @@ -126,15 +127,17 @@ allow-direct-references = true [tool.pytest.ini_options] minversion = "6.0" -addopts = "--ignore=openpilot/ --ignore=opendbc/ --ignore=panda/ --ignore=rednose_repo/ --ignore=tinygrad_repo/ --ignore=teleoprtc_repo/ --ignore=msgq/ -Werror --strict-config --strict-markers --durations=10 -n auto --dist=loadgroup" +addopts = "--ignore=openpilot/ --ignore=opendbc/ --ignore=panda/ --ignore=rednose_repo/ --ignore=tinygrad_repo/ --ignore=teleoprtc_repo/ --ignore=msgq/ -Werror --strict-config --strict-markers --durations=10 -n auto --dist=loadgroup" cpp_files = "test_*" cpp_harness = "selfdrive/test/cpp_harness.py" python_files = "test_*.py" -asyncio_default_fixture_loop_scope = "function" markers = [ "slow: tests that take awhile to run and can be skipped with -m 'not slow'", "tici: tests that are only meant to run on the C3/C3X", - "skip_tici_setup: mark test to skip tici setup fixture" + "skip_tici_setup: mark test to skip tici setup fixture", + "nocapture: don't capture test output", + "shared_download_cache: share download cache between tests", + "xdist_group_class_property: group tests by a property of the class that contains them", ] testpaths = [ "common", @@ -175,9 +178,7 @@ lint.ignore = [ "UP045", "UP007", # these don't play nice with raylib atm ] line-length = 160 -target-version ="py311" exclude = [ - "body", "cereal", "panda", "opendbc", @@ -186,7 +187,7 @@ exclude = [ "tinygrad_repo", "teleoprtc", "teleoprtc_repo", - "third_party", + "third_party/copyparty", "*.ipynb", "generated", ] @@ -196,7 +197,6 @@ lint.flake8-implicit-str-concat.allow-multiline = false "selfdrive".msg = "Use openpilot.selfdrive" "common".msg = "Use openpilot.common" "system".msg = "Use openpilot.system" -"third_party".msg = "Use openpilot.third_party" "tools".msg = "Use openpilot.tools" "pytest.main".msg = "pytest.main requires special handling that is easy to mess up!" "unittest".msg = "Use pytest" @@ -214,7 +214,6 @@ quote-style = "preserve" [tool.ty.src] exclude = [ - "cereal/", "msgq/", "msgq_repo/", "opendbc/", @@ -230,27 +229,16 @@ exclude = [ ] [tool.ty.rules] -# Ignore unresolved imports for Cython-compiled modules (.pyx) -unresolved-import = "ignore" -# Ignore unresolved attributes - many from capnp and Cython modules -unresolved-attribute = "ignore" -# Ignore invalid method overrides - signature variance issues -invalid-method-override = "ignore" -# Ignore possibly-missing-attribute - too many false positives -possibly-missing-attribute = "ignore" -# Ignore invalid assignment - often intentional monkey-patching -invalid-assignment = "ignore" -# Ignore no-matching-overload - numpy/ctypes overload matching issues -no-matching-overload = "ignore" -# Ignore invalid-argument-type - many false positives from raylib, ctypes, numpy -invalid-argument-type = "ignore" -# Ignore call-non-callable - false positives from dynamic types -call-non-callable = "ignore" -# Ignore unsupported-operator - false positives from dynamic types -unsupported-operator = "ignore" -# Ignore not-subscriptable - false positives from dynamic types -not-subscriptable = "ignore" -# not-iterable errors are now fixed +unresolved-import = "ignore" # Cython-compiled modules (.pyx) +unresolved-attribute = "ignore" # many from capnp and Cython modules +invalid-method-override = "ignore" # signature variance issues +possibly-missing-attribute = "ignore" # too many false positives +invalid-assignment = "ignore" # often intentional monkey-patching +no-matching-overload = "ignore" # numpy/ctypes overload matching issues +invalid-argument-type = "ignore" # many false positives from raylib, ctypes, numpy +call-non-callable = "ignore" # false positives from dynamic types +unsupported-operator = "ignore" # false positives from dynamic types +not-subscriptable = "ignore" # false positives from dynamic types [tool.uv] python-preference = "only-managed" diff --git a/release/build_release.sh b/release/build_release.sh index 22d880991f..c038e0e78e 100755 --- a/release/build_release.sh +++ b/release/build_release.sh @@ -16,6 +16,8 @@ if [ -z "$RELEASE_BRANCH" ]; then exit 1 fi +BUILD_BRANCH=release-mici-staging + # set git identity source $DIR/identity.sh @@ -26,7 +28,7 @@ mkdir -p $BUILD_DIR cd $BUILD_DIR git init git remote add origin git@github.com:commaai/openpilot.git -git checkout --orphan $RELEASE_BRANCH +git checkout --orphan $BUILD_BRANCH # do the files copy echo "[-] copying files T=$SECONDS" @@ -46,14 +48,14 @@ git commit -a -m "openpilot v$VERSION release" # Build export PYTHONPATH="$BUILD_DIR" -scons -j$(nproc) --minimal +scons if [ -z "$PANDA_DEBUG_BUILD" ]; then # release panda fw - CERT=/data/pandaextra/certs/release RELEASE=1 scons -j$(nproc) panda/ + CERT=/data/pandaextra/certs/release RELEASE=1 scons panda/ else # build with ALLOW_DEBUG=1 to enable features like experimental longitudinal - scons -j$(nproc) panda/ + scons panda/ fi # Ensure no submodules in release @@ -72,8 +74,8 @@ find . -name '*.pyc' -delete find . -name 'moc_*' -delete find . -name '__pycache__' -delete rm -rf .sconsign.dblite Jenkinsfile release/ -rm -f selfdrive/modeld/models/*.onnx -rm -f sunnypilot/modeld*/models/*.onnx +rm -f selfdrive/modeld/models/*.onnx* +rm -f sunnypilot/modeld*/models/*.onnx* find third_party/ -name '*x86*' -exec rm -r {} + find third_party/ -name '*Darwin*' -exec rm -r {} + @@ -94,9 +96,11 @@ cd $BUILD_DIR RELEASE=1 pytest -n0 -s selfdrive/test/test_onroad.py #pytest selfdrive/car/tests/test_car_interfaces.py -if [ ! -z "$RELEASE_BRANCH" ]; then - echo "[-] pushing release T=$SECONDS" - git push -f origin $RELEASE_BRANCH:$RELEASE_BRANCH -fi +echo "[-] pushing release T=$SECONDS" +REFS=() +for branch in ${RELEASE_BRANCH//,/ }; do + REFS+=("$BUILD_BRANCH:$branch") +done +git push -f origin "${REFS[@]}" echo "[-] done T=$SECONDS" diff --git a/release/build_stripped.sh b/release/build_stripped.sh index df5b2a3dd6..8e73a8aaab 100755 --- a/release/build_stripped.sh +++ b/release/build_stripped.sh @@ -45,6 +45,8 @@ cd $TARGET_DIR rm -rf .git/modules/ rm -f panda/board/obj/panda.bin.signed +find selfdrive/modeld/models -name '*.onnx' -size +95M -exec ./common/file_chunker.py {} \; + # include source commit hash and build date in commit GIT_HASH=$(git --git-dir=$SOURCE_DIR/.git rev-parse HEAD) GIT_COMMIT_DATE=$(git --git-dir=$SOURCE_DIR/.git show --no-patch --format='%ct %ci' HEAD) diff --git a/release/pack.py b/release/pack.py index 8831a0b34d..560500e7a7 100755 --- a/release/pack.py +++ b/release/pack.py @@ -13,7 +13,7 @@ from openpilot.common.basedir import BASEDIR DIRS = ['cereal', 'openpilot'] EXTS = ['.png', '.py', '.ttf', '.capnp', '.json', '.fnt', '.mo', '.po'] -EXCLUDE = ['selfdrive/assets/training', 'third_party/raylib/raylib_repo/examples'] +EXCLUDE = ['selfdrive/assets/training'] INTERPRETER = '/usr/bin/env python3' diff --git a/scripts/lint/check_raylib_includes.sh b/scripts/lint/check_raylib_includes.sh deleted file mode 100755 index e3be73a489..0000000000 --- a/scripts/lint/check_raylib_includes.sh +++ /dev/null @@ -1,10 +0,0 @@ -#!/usr/bin/env bash - -FAIL=0 - -if grep -n '#include "third_party/raylib/include/raylib\.h"' $@ | grep -v '^system/ui/raylib/raylib\.h'; then - echo -e "Bad raylib include found! Use '#include \"system/ui/raylib/raylib.h\"' instead\n" - FAIL=1 -fi - -exit $FAIL diff --git a/scripts/lint/lint.sh b/scripts/lint/lint.sh index 3255c9eb82..919e2ca63a 100755 --- a/scripts/lint/lint.sh +++ b/scripts/lint/lint.sh @@ -14,7 +14,7 @@ cd $ROOT FAILED=0 IGNORED_FILES="uv\.lock|docs\/CARS.md|LICENSE\.md" -IGNORED_DIRS="^third_party.*|^msgq.*|^msgq_repo.*|^opendbc.*|^opendbc_repo.*|^cereal.*|^panda.*|^rednose.*|^rednose_repo.*|^tinygrad.*|^tinygrad_repo.*|^teleoprtc.*|^teleoprtc_repo.*" +IGNORED_DIRS="^msgq.*|^msgq_repo.*|^opendbc.*|^opendbc_repo.*|^cereal.*|^panda.*|^rednose.*|^rednose_repo.*|^tinygrad.*|^tinygrad_repo.*|^teleoprtc.*|^teleoprtc_repo.*|^third_party.*" function run() { shopt -s extglob diff --git a/scripts/reporter.py b/scripts/reporter.py index 93b71761a9..9821a47ccf 100755 --- a/scripts/reporter.py +++ b/scripts/reporter.py @@ -34,6 +34,11 @@ if __name__ == "__main__": for f in glob.glob(BASEDIR + MODEL_PATH + "/*.onnx"): fn = os.path.basename(f) - master = get_checkpoint(MASTER_PATH + MODEL_PATH + fn) + master_path = MASTER_PATH + MODEL_PATH + fn + if os.path.exists(master_path): + master = get_checkpoint(master_path) + master_col = f"[{master}](https://reporter.comma.life/experiment/{master})" + else: + master_col = "N/A (new model)" pr = get_checkpoint(BASEDIR + MODEL_PATH + fn) - print("|", fn, "|", f"[{master}](https://reporterv2.comma.life/{master})", "|", f"[{pr}](https://reporterv2.comma.life/{pr})", "|") + print("|", fn, "|", master_col, "|", f"[{pr}](https://reporter.comma.life/experiment/{pr})", "|") diff --git a/selfdrive/assets/assets.qrc b/selfdrive/assets/assets.qrc index 26a7d998ed..72e2f7f3c0 100644 --- a/selfdrive/assets/assets.qrc +++ b/selfdrive/assets/assets.qrc @@ -1,6 +1,6 @@ - ../../third_party/bootstrap/bootstrap-icons.svg + @BOOTSTRAP_ICONS_SVG@ images/button_continue_triangle.svg icons/circled_check.svg icons/circled_slash.svg diff --git a/selfdrive/assets/fonts/process.py b/selfdrive/assets/fonts/process.py index 30ccf9ca55..62ae6ec684 100755 --- a/selfdrive/assets/fonts/process.py +++ b/selfdrive/assets/fonts/process.py @@ -37,10 +37,10 @@ def _char_sets(): return tuple(sorted(ord(c) for c in base)), tuple(sorted(ord(c) for c in unifont)) -def _glyph_metrics(glyphs, rects, codepoints): +def _glyph_metrics(glyphs, rects, glyph_count: int): entries = [] min_offset_y, max_extent = None, 0 - for idx, codepoint in enumerate(codepoints): + for idx in range(glyph_count): glyph = glyphs[idx] rect = rects[idx] width = int(round(rect.width)) @@ -49,7 +49,7 @@ def _glyph_metrics(glyphs, rects, codepoints): min_offset_y = offset_y if min_offset_y is None else min(min_offset_y, offset_y) max_extent = max(max_extent, offset_y + height) entries.append({ - "id": codepoint, + "id": glyph.value, "x": int(round(rect.x)), "y": int(round(rect.y)), "width": width, @@ -97,19 +97,23 @@ def _process_font(font_path: Path, codepoints: tuple[int, ...]): file_buf = rl.ffi.new("unsigned char[]", data) cp_buffer = rl.ffi.new("int[]", codepoints) cp_ptr = rl.ffi.cast("int *", cp_buffer) - glyphs = rl.load_font_data(rl.ffi.cast("unsigned char *", file_buf), len(data), font_size, cp_ptr, len(codepoints), rl.FontType.FONT_DEFAULT) + glyph_count = rl.ffi.new("int *", len(codepoints)) + glyphs = rl.load_font_data( + rl.ffi.cast("unsigned char *", file_buf), len(data), font_size, cp_ptr, len(codepoints), + rl.FontType.FONT_DEFAULT, glyph_count + ) if glyphs == rl.ffi.NULL: raise RuntimeError("raylib failed to load font data") rects_ptr = rl.ffi.new("Rectangle **") - image = rl.gen_image_font_atlas(glyphs, rects_ptr, len(codepoints), font_size, GLYPH_PADDING, 0) + image = rl.gen_image_font_atlas(glyphs, rects_ptr, glyph_count[0], font_size, GLYPH_PADDING, 0) if image.width == 0 or image.height == 0: raise RuntimeError("raylib returned an empty atlas") rects = rects_ptr[0] atlas_name = f"{font_path.stem}.png" atlas_path = FONT_DIR / atlas_name - entries, line_height, base = _glyph_metrics(glyphs, rects, codepoints) + entries, line_height, base = _glyph_metrics(glyphs, rects, glyph_count[0]) if not rl.export_image(image, atlas_path.as_posix()): raise RuntimeError("Failed to export atlas image") diff --git a/selfdrive/assets/icons_mici/body.png b/selfdrive/assets/icons_mici/body.png new file mode 100644 index 0000000000..2f7bb779d1 --- /dev/null +++ b/selfdrive/assets/icons_mici/body.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:6b45f88128430fb50ef51c8e08b8e2a1c8fbe0b5c3a08de9f5d9d59bc1edc82e +size 4545 diff --git a/selfdrive/assets/icons_mici/egpu.png b/selfdrive/assets/icons_mici/egpu.png new file mode 100644 index 0000000000..dc2bc8e276 --- /dev/null +++ b/selfdrive/assets/icons_mici/egpu.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:ec3dcf64cbc34251d8423cb8b3b31d743e93d14002dec43c389a857cb7e8eb17 +size 10875 diff --git a/selfdrive/assets/icons_mici/egpu_gray.png b/selfdrive/assets/icons_mici/egpu_gray.png new file mode 100644 index 0000000000..a6aeb84689 --- /dev/null +++ b/selfdrive/assets/icons_mici/egpu_gray.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:7409c53d7c72681c24982fd83b56ce70f80797c9c0f936d9296a5c18557ac472 +size 7279 diff --git a/selfdrive/assets/icons_mici/onroad/driver_monitoring/dm_cone.png b/selfdrive/assets/icons_mici/onroad/driver_monitoring/dm_cone.png index ec2f948998..6974b6d8e2 100644 --- a/selfdrive/assets/icons_mici/onroad/driver_monitoring/dm_cone.png +++ b/selfdrive/assets/icons_mici/onroad/driver_monitoring/dm_cone.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:26b3660dbd1e60b0ba98914afa7cb3a67151bb6990d218f55c901f243e38ff3e -size 3631 +oid sha256:5f5d4b7bd406114945e53f4d56089102ee83ba7d0a4590a371f7acab90c7ad53 +size 1862 diff --git a/selfdrive/assets/prep-svg.sh b/selfdrive/assets/prep-svg.sh index 2332cd25c5..567c17da32 100755 --- a/selfdrive/assets/prep-svg.sh +++ b/selfdrive/assets/prep-svg.sh @@ -3,7 +3,7 @@ set -e DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )" ICONS_DIR="$DIR/icons" -BOOTSTRAP_SVG="$DIR/../../third_party/bootstrap/bootstrap-icons.svg" +BOOTSTRAP_SVG="$(python3 -c 'import bootstrap_icons; print(bootstrap_icons.SVG_PATH)')" ICON_IDS=( arrow-right diff --git a/selfdrive/car/car_specific.py b/selfdrive/car/car_specific.py index 86494afc7a..baa29978e3 100644 --- a/selfdrive/car/car_specific.py +++ b/selfdrive/car/car_specific.py @@ -73,7 +73,7 @@ class CarSpecificEvents: elif self.CP.brand == 'gm': # Enabling at a standstill with brake is allowed # TODO: verify 17 Volt can enable for the first time at a stop and allow for all GMs - if CS.vEgo < self.CP.minEnableSpeed and not (CS.standstill and CS.brake >= 20 and + if CS.vEgo < self.CP.minEnableSpeed and not (CS.standstill and CS.brakePressed and self.CP.networkLocation == NetworkLocation.fwdCamera): events.add(EventName.belowEngageSpeed) if CS.cruiseState.standstill: diff --git a/selfdrive/car/card.py b/selfdrive/car/card.py index c4c81d26e3..995d02aabc 100755 --- a/selfdrive/car/card.py +++ b/selfdrive/car/card.py @@ -37,7 +37,7 @@ def obd_callback(params: Params) -> ObdCallback: if params.get_bool("ObdMultiplexingEnabled") != obd_multiplexing: cloudlog.warning(f"Setting OBD multiplexing to {obd_multiplexing}") params.remove("ObdMultiplexingChanged") - params.put_bool("ObdMultiplexingEnabled", obd_multiplexing) + params.put_bool("ObdMultiplexingEnabled", obd_multiplexing, block=True) params.get_bool("ObdMultiplexingChanged", block=True) cloudlog.warning("OBD multiplexing set successfully") return set_obd_multiplexing @@ -116,7 +116,7 @@ class Car: self.CP_SP = self.CI.CP_SP # continue onto next fingerprinting step in pandad - self.params.put_bool("FirmwareQueryDone", True) + self.params.put_bool("FirmwareQueryDone", True, block=True) else: self.CI, self.CP, self.CP_SP = CI, CI.CP, CI.CP_SP self.RI = RI @@ -143,7 +143,7 @@ class Car: with open("/cache/params/SecOCKey") as f: user_key = f.readline().strip() if len(user_key) == 32: - self.params.put("SecOCKey", user_key) + self.params.put("SecOCKey", user_key, block=True) except Exception: pass @@ -161,21 +161,21 @@ class Car: # Write previous route's CarParams prev_cp = self.params.get("CarParamsPersistent") if prev_cp is not None: - self.params.put("CarParamsPrevRoute", prev_cp) + self.params.put("CarParamsPrevRoute", prev_cp, block=True) # Write CarParams for controls and radard cp_bytes = self.CP.to_bytes() - self.params.put("CarParams", cp_bytes) - self.params.put_nonblocking("CarParamsCache", cp_bytes) - self.params.put_nonblocking("CarParamsPersistent", cp_bytes) + self.params.put("CarParams", cp_bytes, block=True) + self.params.put("CarParamsCache", cp_bytes) + self.params.put("CarParamsPersistent", cp_bytes) # Write CarParamsSP for controls # convert to pycapnp representation for caching and logging self.CP_SP_capnp = convert_to_capnp(self.CP_SP) cp_sp_bytes = self.CP_SP_capnp.to_bytes() - self.params.put("CarParamsSP", cp_sp_bytes) - self.params.put_nonblocking("CarParamsSPCache", cp_sp_bytes) - self.params.put_nonblocking("CarParamsSPPersistent", cp_sp_bytes) + self.params.put("CarParamsSP", cp_sp_bytes, block=True) + self.params.put("CarParamsSPCache", cp_sp_bytes) + self.params.put("CarParamsSPPersistent", cp_sp_bytes) self.v_cruise_helper = VCruiseHelper(self.CP, self.CP_SP) @@ -274,7 +274,7 @@ class Car: # TODO: this can make us miss at least a few cycles when doing an ECU knockout self.CI.init(self.CP, self.CP_SP, *self.can_callbacks) # signal pandad to switch to car safety mode - self.params.put_bool_nonblocking("ControlsReady", True) + self.params.put_bool("ControlsReady", True) if self.sm.all_alive(['carControl']): # send car controls over can diff --git a/selfdrive/car/tests/test_cruise_speed.py b/selfdrive/car/tests/test_cruise_speed.py index d3ca6eed4f..360c93c25b 100644 --- a/selfdrive/car/tests/test_cruise_speed.py +++ b/selfdrive/car/tests/test_cruise_speed.py @@ -94,7 +94,7 @@ class TestVCruiseHelper: self.enable(V_CRUISE_INITIAL * CV.KPH_TO_MS, False, False) # Expected diff on enabling. Speed should not change on falling edge of pressed - assert not pressed == self.v_cruise_helper.v_cruise_kph == self.v_cruise_helper.v_cruise_kph_last + assert (not pressed) == (self.v_cruise_helper.v_cruise_kph == self.v_cruise_helper.v_cruise_kph_last) def test_resume_in_standstill(self): """ diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py index 209df3b159..a99e8b9d1d 100644 --- a/selfdrive/car/tests/test_models.py +++ b/selfdrive/car/tests/test_models.py @@ -13,7 +13,7 @@ from opendbc.car import DT_CTRL, gen_empty_fingerprint, structs from opendbc.car.can_definitions import CanData from opendbc.car.car_helpers import FRAME_FINGERPRINT, interfaces from opendbc.car.fingerprints import MIGRATION -from opendbc.car.honda.values import CAR as HONDA, HondaFlags +from opendbc.car.honda.values import HondaFlags from opendbc.car.structs import car from opendbc.car.tests.routes import non_tested_cars, routes, CarTestRoute from opendbc.car.values import Platform, PLATFORMS @@ -28,6 +28,14 @@ from openpilot.tools.lib.route import SegmentName SafetyModel = car.CarParams.SafetyModel SteerControlType = structs.CarParams.SteerControlType +# panda safety stores angle_meas in brand-specific CAN units (angle_deg_to_can in opendbc/safety/modes/*.h). +ANGLE_DEG_TO_CAN = { + "tesla": -10, + "toyota": 17.452007, + "nissan": 100, + "psa": 10, +} + NUM_JOBS = int(os.environ.get("NUM_JOBS", "1")) JOB_ID = int(os.environ.get("JOB_ID", "0")) INTERNAL_SEG_LIST = os.environ.get("INTERNAL_SEG_LIST", "") @@ -350,13 +358,7 @@ class TestCarModelBase(unittest.TestCase): self.assertEqual(CS.gasPressed, self.safety.get_gas_pressed_prev()) if self.safety.get_brake_pressed_prev() != prev_panda_brake: - # TODO: remove this exception once this mismatch is resolved - brake_pressed = CS.brakePressed - if CS.brakePressed and not self.safety.get_brake_pressed_prev(): - if self.CP.carFingerprint in (HONDA.HONDA_PILOT, HONDA.HONDA_RIDGELINE) and CS.brake > 0.05: - brake_pressed = False - - self.assertEqual(brake_pressed, self.safety.get_brake_pressed_prev()) + self.assertEqual(CS.brakePressed, self.safety.get_brake_pressed_prev()) if self.safety.get_regen_braking_prev() != prev_panda_regen_braking: self.assertEqual(CS.regenBraking, self.safety.get_regen_braking_prev()) @@ -433,12 +435,14 @@ class TestCarModelBase(unittest.TestCase): checks['vEgoRaw'] += (v_ego_raw > (self.safety.get_vehicle_speed_max() + 1e-3) or v_ego_raw < (self.safety.get_vehicle_speed_min() - 1e-3)) - # TODO: remove this exception once this mismatch is resolved - brake_pressed = CS.brakePressed - if CS.brakePressed and not self.safety.get_brake_pressed_prev(): - if self.CP.carFingerprint in (HONDA.HONDA_PILOT, HONDA.HONDA_RIDGELINE) and CS.brake > 0.05: - brake_pressed = False - checks['brakePressed'] += brake_pressed != self.safety.get_brake_pressed_prev() + # check steering angle for angle control cars (panda stores angle_meas in CAN units) + # ford excluded since it tracks curvature, not steering angle + if self.CP.steerControlType == SteerControlType.angle and not self.CP.notCar and self.CP.brand != "ford": + angle_can = (CS.steeringAngleDeg + CS.steeringAngleOffsetDeg) * ANGLE_DEG_TO_CAN[self.CP.brand] + checks['steeringAngleDeg'] += (angle_can > (self.safety.get_angle_meas_max() + 1) or + angle_can < (self.safety.get_angle_meas_min() - 1)) + + checks['brakePressed'] += CS.brakePressed != 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() diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index b53185ca2b..c242871125 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -212,7 +212,7 @@ class Controls(ControlsExt): cs.upAccelCmd = float(self.LoC.pid.p) cs.uiAccelCmd = float(self.LoC.pid.i) cs.ufAccelCmd = float(self.LoC.pid.f) - cs.forceDecel = bool((self.sm['driverMonitoringState'].awarenessStatus < 0.) or + cs.forceDecel = bool((self.sm['driverMonitoringState'].alertLevel == log.DriverMonitoringState.AlertLevel.three) or (self.sm['selfdriveState'].state == State.softDisabling)) lat_tuning = self.CP.lateralTuning.which() diff --git a/selfdrive/controls/lib/drive_helpers.py b/selfdrive/controls/lib/drive_helpers.py index 1e2fb27b51..5392ff8875 100644 --- a/selfdrive/controls/lib/drive_helpers.py +++ b/selfdrive/controls/lib/drive_helpers.py @@ -8,6 +8,7 @@ CAR_ROTATION_RADIUS = 0.0 # This is a turn radius smaller than most cars can achieve MAX_CURVATURE = 0.2 MAX_VEL_ERR = 5.0 # m/s +MIN_STABLE_DELAY = 0.3 # EU guidelines MAX_LATERAL_JERK = 5.0 # m/s^3 @@ -43,7 +44,10 @@ def get_accel_from_plan(speeds, accels, t_idxs, action_t=DT_MDL, vEgoStopping=0. if len(speeds) == len(t_idxs): v_now = speeds[0] a_now = accels[0] - v_target = np.interp(action_t, t_idxs, speeds) + if action_t < MIN_STABLE_DELAY: + v_target = v_now + (action_t / MIN_STABLE_DELAY) * (np.interp(MIN_STABLE_DELAY, t_idxs, speeds) - v_now) + else: + v_target = np.interp(action_t, t_idxs, speeds) a_target = 2 * (v_target - v_now) / (action_t) - a_now else: v_now = 0.0 @@ -58,6 +62,9 @@ def curv_from_psis(psi_target, psi_rate, 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) + if action_t < MIN_STABLE_DELAY: + psi_target = (action_t / MIN_STABLE_DELAY) * np.interp(MIN_STABLE_DELAY, t_idxs, yaws) + else: + 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/lateral_mpc_lib/SConscript b/selfdrive/controls/lib/lateral_mpc_lib/SConscript index c9ebf89207..5ff526ae83 100644 --- a/selfdrive/controls/lib/lateral_mpc_lib/SConscript +++ b/selfdrive/controls/lib/lateral_mpc_lib/SConscript @@ -1,4 +1,4 @@ -Import('env', 'envCython', 'arch', 'msgq_python', 'common_python', 'np_version') +Import('env', 'envCython', 'arch', 'msgq_python', 'common_python', 'np_version', 'acados') gen = "c_generated_code" @@ -45,18 +45,24 @@ generated_files = [ f'{gen}/lat_cost/lat_cost.h', ] + build_files -acados_dir = '#third_party/acados' -acados_templates_dir = '#third_party/acados/acados_template/c_templates_tera' +acados_include_dir = Dir(acados.INCLUDE_DIR) +acados_template_dir = Dir(acados.TEMPLATE_DIR) source_list = ['lat_mpc.py', '#selfdrive/modeld/constants.py', - f'{acados_dir}/include/acados_c/ocp_nlp_interface.h', - f'{acados_templates_dir}/acados_solver.in.c', + acados_include_dir.File('acados_c/ocp_nlp_interface.h'), + acados_template_dir.File('c_templates_tera/acados_solver.in.c'), ] lenv = env.Clone() -acados_rel_path = Dir(gen).rel_path(Dir(f"#third_party/acados/{arch}/lib")) -lenv["RPATH"] += [lenv.Literal(f'\\$$ORIGIN/{acados_rel_path}')] +copied_acados_libs = [] +if arch != "Darwin": + for lib in ["libacados.so", "libblasfeo.so", "libhpipm.so", "libqpOASES_e.so.3.1"]: + copied_acados_libs += lenv.Command(f"{gen}/{lib}", Dir(acados.LIB_DIR).File(lib), [Mkdir(Dir(gen)), Copy("$TARGET", "$SOURCE")]) + lenv["RPATH"] += [lenv.Literal('\\$$ORIGIN')] +else: + acados_rel_path = Dir(gen).rel_path(Dir(acados.LIB_DIR)) + lenv["RPATH"] += [lenv.Literal(f'\\$$ORIGIN/{acados_rel_path}')] lenv.Clean(generated_files, Dir(gen)) generated_lat = lenv.Command(generated_files, @@ -77,8 +83,8 @@ lib_solver = lenv.SharedLibrary(f"{gen}/acados_ocp_solver_lat", LIBS=['m', 'acados', 'hpipm', 'blasfeo', 'qpOASES_e']) # generate cython stuff -acados_ocp_solver_pyx = File("#third_party/acados/acados_template/acados_ocp_solver_pyx.pyx") -acados_ocp_solver_common = File("#third_party/acados/acados_template/acados_solver_common.pxd") +acados_ocp_solver_pyx = acados_template_dir.File('acados_ocp_solver_pyx.pyx') +acados_ocp_solver_common = acados_template_dir.File('acados_solver_common.pxd') libacados_ocp_solver_pxd = File(f'{gen}/acados_solver.pxd') libacados_ocp_solver_c = File(f'{gen}/acados_ocp_solver_pyx.c') @@ -94,4 +100,5 @@ lenv2.Command(libacados_ocp_solver_c, f' {acados_ocp_solver_pyx.get_labspath()}') lib_cython = lenv2.Program(f'{gen}/acados_ocp_solver_pyx.so', [libacados_ocp_solver_c], LIBS=['acados_ocp_solver_lat']) lenv2.Depends(lib_cython, lib_solver) +lenv2.Depends(lib_cython, copied_acados_libs) lenv2.Depends(libacados_ocp_solver_c, np_version) diff --git a/selfdrive/controls/lib/lateral_mpc_lib/lat_mpc.py b/selfdrive/controls/lib/lateral_mpc_lib/lat_mpc.py index ad60861088..3b597b2e42 100755 --- a/selfdrive/controls/lib/lateral_mpc_lib/lat_mpc.py +++ b/selfdrive/controls/lib/lateral_mpc_lib/lat_mpc.py @@ -8,7 +8,7 @@ from casadi import SX, vertcat, sin, cos from openpilot.selfdrive.modeld.constants import ModelConstants if __name__ == '__main__': # generating code - from openpilot.third_party.acados.acados_template import AcadosModel, AcadosOcp, AcadosOcpSolver + from acados.acados_template import AcadosModel, AcadosOcp, AcadosOcpSolver else: from openpilot.selfdrive.controls.lib.lateral_mpc_lib.c_generated_code.acados_ocp_solver_pyx import AcadosOcpSolverCython diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript b/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript index 7a6c02a538..a3218e9f34 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript @@ -1,4 +1,4 @@ -Import('env', 'envCython', 'arch', 'msgq_python', 'common_python', 'np_version') +Import('env', 'envCython', 'arch', 'msgq_python', 'common_python', 'np_version', 'acados') gen = "c_generated_code" @@ -51,18 +51,24 @@ generated_files = [ f'{gen}/long_cost/long_cost.h', ] + build_files -acados_dir = '#third_party/acados' -acados_templates_dir = '#third_party/acados/acados_template/c_templates_tera' +acados_include_dir = Dir(acados.INCLUDE_DIR) +acados_template_dir = Dir(acados.TEMPLATE_DIR) source_list = ['long_mpc.py', '#selfdrive/modeld/constants.py', - f'{acados_dir}/include/acados_c/ocp_nlp_interface.h', - f'{acados_templates_dir}/acados_solver.in.c', + acados_include_dir.File('acados_c/ocp_nlp_interface.h'), + acados_template_dir.File('c_templates_tera/acados_solver.in.c'), ] lenv = env.Clone() -acados_rel_path = Dir(gen).rel_path(Dir(f"#third_party/acados/{arch}/lib")) -lenv["RPATH"] += [lenv.Literal(f'\\$$ORIGIN/{acados_rel_path}')] +copied_acados_libs = [] +if arch != "Darwin": + for lib in ["libacados.so", "libblasfeo.so", "libhpipm.so", "libqpOASES_e.so.3.1"]: + copied_acados_libs += lenv.Command(f"{gen}/{lib}", Dir(acados.LIB_DIR).File(lib), [Mkdir(Dir(gen)), Copy("$TARGET", "$SOURCE")]) + lenv["RPATH"] += [lenv.Literal('\\$$ORIGIN')] +else: + acados_rel_path = Dir(gen).rel_path(Dir(acados.LIB_DIR)) + lenv["RPATH"] += [lenv.Literal(f'\\$$ORIGIN/{acados_rel_path}')] lenv.Clean(generated_files, Dir(gen)) generated_long = lenv.Command(generated_files, source_list, @@ -82,8 +88,8 @@ lib_solver = lenv.SharedLibrary(f"{gen}/acados_ocp_solver_long", LIBS=['m', 'acados', 'hpipm', 'blasfeo', 'qpOASES_e']) # generate cython stuff -acados_ocp_solver_pyx = File("#third_party/acados/acados_template/acados_ocp_solver_pyx.pyx") -acados_ocp_solver_common = File("#third_party/acados/acados_template/acados_solver_common.pxd") +acados_ocp_solver_pyx = acados_template_dir.File('acados_ocp_solver_pyx.pyx') +acados_ocp_solver_common = acados_template_dir.File('acados_solver_common.pxd') libacados_ocp_solver_pxd = File(f'{gen}/acados_solver.pxd') libacados_ocp_solver_c = File(f'{gen}/acados_ocp_solver_pyx.c') @@ -99,4 +105,5 @@ lenv2.Command(libacados_ocp_solver_c, f' {acados_ocp_solver_pyx.get_labspath()}') lib_cython = lenv2.Program(f'{gen}/acados_ocp_solver_pyx.so', [libacados_ocp_solver_c], LIBS=['acados_ocp_solver_long']) lenv2.Depends(lib_cython, lib_solver) +lenv2.Depends(lib_cython, copied_acados_libs) lenv2.Depends(libacados_ocp_solver_c, np_version) diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py index efdef9dd71..deae416489 100755 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py @@ -11,7 +11,7 @@ from openpilot.selfdrive.modeld.constants import index_function from openpilot.selfdrive.controls.radard import _LEAD_ACCEL_TAU if __name__ == '__main__': # generating code - from openpilot.third_party.acados.acados_template import AcadosModel, AcadosOcp, AcadosOcpSolver + from acados.acados_template import AcadosModel, AcadosOcp, AcadosOcpSolver else: from openpilot.selfdrive.controls.lib.longitudinal_mpc_lib.c_generated_code.acados_ocp_solver_pyx import AcadosOcpSolverCython diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py index bee4244054..d51eb6edb0 100755 --- a/selfdrive/controls/radard.py +++ b/selfdrive/controls/radard.py @@ -142,7 +142,7 @@ def match_vision_to_track(v_ego: float, lead: capnp._DynamicStructReader, tracks return None -def get_RadarState_from_vision(lead_msg: capnp._DynamicStructReader, v_ego: float, model_v_ego: float): +def get_RadarState_from_vision(lead_msg: capnp._DynamicStructReader, v_ego: float, model_v_ego: float, lead_prob: float): lead_v_rel_pred = lead_msg.v[0] - model_v_ego return { "dRel": float(lead_msg.x[0] - RADAR_TO_CAMERA), @@ -153,7 +153,7 @@ def get_RadarState_from_vision(lead_msg: capnp._DynamicStructReader, v_ego: floa "aLeadK": float(lead_msg.a[0]), "aLeadTau": 0.3, "fcw": False, - "modelProb": float(lead_msg.prob), + "modelProb": float(lead_prob), "status": True, "radar": False, "radarTrackId": -1, @@ -161,19 +161,20 @@ def get_RadarState_from_vision(lead_msg: capnp._DynamicStructReader, v_ego: floa def get_lead(v_ego: float, ready: bool, tracks: dict[int, Track], lead_msg: capnp._DynamicStructReader, - model_v_ego: float, CP: structs.CarParams, CP_SP: structs.CarParamsSP, low_speed_override: bool = True) -> dict[str, Any]: + model_v_ego: float, lead_prob: float, CP: structs.CarParams, CP_SP: structs.CarParamsSP, + low_speed_override: bool = True) -> dict[str, Any]: # Determine leads, this is where the essential logic happens - if len(tracks) > 0 and ready and lead_msg.prob > .5: + if len(tracks) > 0 and ready and lead_prob > .5: track = match_vision_to_track(v_ego, lead_msg, tracks) else: track = None lead_dict = {'status': False} if track is not None: - lead_dict = track.get_RadarState(lead_msg.prob) + lead_dict = track.get_RadarState(lead_prob) lead_dict = get_custom_yrel(CP, CP_SP, lead_dict, lead_msg) - elif (track is None) and ready and (lead_msg.prob > .5): - lead_dict = get_RadarState_from_vision(lead_msg, v_ego, model_v_ego) + elif (track is None) and ready and (lead_prob > .5): + lead_dict = get_RadarState_from_vision(lead_msg, v_ego, model_v_ego, lead_prob) if low_speed_override: low_speed_tracks = [c for c in tracks.values() if c.potential_low_speed_lead(v_ego)] @@ -205,6 +206,7 @@ class RadarD: self.tracks: dict[int, Track] = {} self.kalman_params = KalmanParams(DT_MDL) + self.lead_prob_filters = [FirstOrderFilter(0.0, 0.2, DT_MDL) for _ in range(2)] self.v_ego = 0.0 self.v_ego_hist = deque([0.0], maxlen=int(round(delay / DT_MDL))+1) @@ -256,8 +258,18 @@ class RadarD: model_v_ego = self.v_ego leads_v3 = sm['modelV2'].leadsV3 if len(leads_v3) > 1: - self.radar_state.leadOne = get_lead(self.v_ego, self.ready, self.tracks, leads_v3[0], model_v_ego, self.CP, self.CP_SP, low_speed_override=True) - self.radar_state.leadTwo = get_lead(self.v_ego, self.ready, self.tracks, leads_v3[1], model_v_ego, self.CP, self.CP_SP, low_speed_override=False) + for i in range(2): + # Asymmetric filter on lead prob to keep lead when uncertain + lead_prob = leads_v3[i].prob + if lead_prob > self.lead_prob_filters[i].x: + self.lead_prob_filters[i].x = lead_prob + else: + self.lead_prob_filters[i].update(lead_prob) + + self.radar_state.leadOne = get_lead(self.v_ego, self.ready, self.tracks, leads_v3[0], model_v_ego, self.lead_prob_filters[0].x, + self.CP, self.CP_SP, low_speed_override=True) + self.radar_state.leadTwo = get_lead(self.v_ego, self.ready, self.tracks, leads_v3[1], model_v_ego, self.lead_prob_filters[1].x, + self.CP, self.CP_SP, low_speed_override=False) def publish(self, pm: messaging.PubMaster): assert self.radar_state is not None diff --git a/selfdrive/debug/car/ecu_addrs.py b/selfdrive/debug/car/ecu_addrs.py index 584c930ebf..f3f06406c0 100755 --- a/selfdrive/debug/car/ecu_addrs.py +++ b/selfdrive/debug/car/ecu_addrs.py @@ -26,9 +26,9 @@ if __name__ == "__main__": # Set up params for pandad params = Params() params.remove("FirmwareQueryDone") - params.put_bool("IsOnroad", False) + params.put_bool("IsOnroad", False, block=True) time.sleep(0.2) # thread is 10 Hz - params.put_bool("IsOnroad", True) + params.put_bool("IsOnroad", True, block=True) obd_callback(params)(not args.no_obd) diff --git a/selfdrive/debug/car/fw_versions.py b/selfdrive/debug/car/fw_versions.py index 5fb65e6972..b04f9cd2a6 100755 --- a/selfdrive/debug/car/fw_versions.py +++ b/selfdrive/debug/car/fw_versions.py @@ -30,9 +30,9 @@ if __name__ == "__main__": # Set up params for pandad params = Params() params.remove("FirmwareQueryDone") - params.put_bool("IsOnroad", False) + params.put_bool("IsOnroad", False, block=True) time.sleep(0.2) # thread is 10 Hz - params.put_bool("IsOnroad", True) + params.put_bool("IsOnroad", True, block=True) set_obd_multiplexing = obd_callback(params) extra: Any = None diff --git a/selfdrive/debug/set_car_params.py b/selfdrive/debug/set_car_params.py index aec30b4d74..dabb6b7065 100755 --- a/selfdrive/debug/set_car_params.py +++ b/selfdrive/debug/set_car_params.py @@ -19,4 +19,4 @@ if __name__ == "__main__": cp_bytes = CP.to_bytes() for p in ("CarParams", "CarParamsCache", "CarParamsPersistent"): - Params().put(p, cp_bytes) + Params().put(p, cp_bytes, block=True) diff --git a/selfdrive/debug/uiview.py b/selfdrive/debug/uiview.py index eac1f8fbf4..2cd541363c 100755 --- a/selfdrive/debug/uiview.py +++ b/selfdrive/debug/uiview.py @@ -9,7 +9,7 @@ from openpilot.system.hardware import HARDWARE if __name__ == "__main__": CP = car.CarParams(notCar=True, wheelbase=1, steerRatio=10) params = Params() - params.put("CarParams", CP.to_bytes()) + params.put("CarParams", CP.to_bytes(), block=True) if use_tinygrad_modeld := is_tinygrad_model(False, params, CP): print("Using TinyGrad modeld") diff --git a/selfdrive/locationd/calibrationd.py b/selfdrive/locationd/calibrationd.py index 036f5822d2..4423f39061 100755 --- a/selfdrive/locationd/calibrationd.py +++ b/selfdrive/locationd/calibrationd.py @@ -167,7 +167,7 @@ class Calibrator: write_this_cycle = (self.idx == 0) and (self.block_idx % (INPUTS_WANTED//5) == 5) if self.param_put and write_this_cycle: - self.params.put_nonblocking("CalibrationParams", self.get_msg(True).to_bytes()) + self.params.put("CalibrationParams", self.get_msg(True).to_bytes()) def handle_v_ego(self, v_ego: float) -> None: self.v_ego = v_ego diff --git a/selfdrive/locationd/lagd.py b/selfdrive/locationd/lagd.py index d037af613a..2980e61e5e 100755 --- a/selfdrive/locationd/lagd.py +++ b/selfdrive/locationd/lagd.py @@ -414,7 +414,7 @@ def main(): pm.send('liveDelay', lag_msg_dat) if sm.frame % 1200 == 0: # cache every 60 seconds - params.put_nonblocking("LiveDelay", lag_msg_dat) + params.put("LiveDelay", lag_msg_dat) if sm.frame % 60 == 0: # read from and write to params every 3 seconds lagd_toggle.update(lag_msg) diff --git a/selfdrive/locationd/paramsd.py b/selfdrive/locationd/paramsd.py index 0489ae4174..02d09c506e 100755 --- a/selfdrive/locationd/paramsd.py +++ b/selfdrive/locationd/paramsd.py @@ -212,7 +212,7 @@ def migrate_cached_vehicle_params_if_needed(params: Params): last_parameters_msg.liveParameters.steerRatio = last_parameters_data_old['steerRatio'] last_parameters_msg.liveParameters.stiffnessFactor = last_parameters_data_old['stiffnessFactor'] last_parameters_msg.liveParameters.angleOffsetAverageDeg = last_parameters_data_old['angleOffsetAverageDeg'] - params.put("LiveParametersV2", last_parameters_msg.to_bytes()) + params.put("LiveParametersV2", last_parameters_msg.to_bytes(), block=True) except Exception as e: cloudlog.error(f"Failed to perform parameter migration: {e}") params.remove("LiveParameters") @@ -290,7 +290,7 @@ def main(): msg_dat = msg.to_bytes() if sm.frame % 1200 == 0: # once a minute - params.put_nonblocking("LiveParametersV2", msg_dat) + params.put("LiveParametersV2", msg_dat) pm.send('liveParameters', msg_dat) diff --git a/selfdrive/locationd/test/test_calibrationd.py b/selfdrive/locationd/test/test_calibrationd.py index df61b6a7c7..c90ce506ab 100644 --- a/selfdrive/locationd/test/test_calibrationd.py +++ b/selfdrive/locationd/test/test_calibrationd.py @@ -36,7 +36,7 @@ class TestCalibrationd: msg.liveCalibration.validBlocks = random.randint(1, 10) msg.liveCalibration.rpyCalib = [random.random() for _ in range(3)] msg.liveCalibration.height = [random.random() for _ in range(1)] - Params().put("CalibrationParams", msg.to_bytes()) + Params().put("CalibrationParams", msg.to_bytes(), block=True) c = Calibrator(param_put=True) np.testing.assert_allclose(msg.liveCalibration.rpyCalib, c.rpy) diff --git a/selfdrive/locationd/test/test_lagd.py b/selfdrive/locationd/test/test_lagd.py index 6249e6b04b..746f7ad478 100644 --- a/selfdrive/locationd/test/test_lagd.py +++ b/selfdrive/locationd/test/test_lagd.py @@ -53,8 +53,8 @@ class TestLagd: 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()) + params.put("LiveDelay", msg.to_bytes(), block=True) + params.put("CarParamsPrevRoute", CP.as_builder().to_bytes(), block=True) saved_lag_params = retrieve_initial_lag(params, CP) assert saved_lag_params is not None diff --git a/selfdrive/locationd/test/test_paramsd.py b/selfdrive/locationd/test/test_paramsd.py index dd496b7675..1a4d348e94 100644 --- a/selfdrive/locationd/test/test_paramsd.py +++ b/selfdrive/locationd/test/test_paramsd.py @@ -27,8 +27,8 @@ class TestParamsd: 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()) + params.put("LiveParametersV2", msg.to_bytes(), block=True) + params.put("CarParamsPrevRoute", CP.as_builder().to_bytes(), block=True) 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) @@ -46,8 +46,8 @@ class TestParamsd: CP = next(m for m in lr if m.which() == "carParams").carParams msg = get_random_live_parameters(CP) - params.put("LiveParameters", msg.liveParameters.to_dict()) - params.put("CarParamsPrevRoute", CP.as_builder().to_bytes()) + params.put("LiveParameters", msg.liveParameters.to_dict(), block=True) + params.put("CarParamsPrevRoute", CP.as_builder().to_bytes(), block=True) params.remove("LiveParametersV2") migrate_cached_vehicle_params_if_needed(params) @@ -59,7 +59,7 @@ class TestParamsd: def test_read_saved_params_corrupted_old_format(self): params = Params() - params.put("LiveParameters", {}) + params.put("LiveParameters", {}, block=True) params.remove("LiveParametersV2") migrate_cached_vehicle_params_if_needed(params) diff --git a/selfdrive/locationd/torqued.py b/selfdrive/locationd/torqued.py index 28731d2ad7..a0f16f303a 100755 --- a/selfdrive/locationd/torqued.py +++ b/selfdrive/locationd/torqued.py @@ -278,7 +278,7 @@ def main(demo=False): # Cache points every 60 seconds while onroad if sm.frame % 240 == 0: msg = estimator.get_msg(valid=sm.all_checks(), with_points=True) - params.put_nonblocking("LiveTorqueParameters", msg.to_bytes()) + params.put("LiveTorqueParameters", msg.to_bytes()) if __name__ == "__main__": diff --git a/selfdrive/modeld/SConscript b/selfdrive/modeld/SConscript index 544fcafc77..80a7df4515 100644 --- a/selfdrive/modeld/SConscript +++ b/selfdrive/modeld/SConscript @@ -1,9 +1,19 @@ import glob import json import os -from SCons.Script import Value -from openpilot.common.file_chunker import chunk_file, get_chunk_paths -from tinygrad import Device +import sys, subprocess +from SCons.Script import Action, Value +from openpilot.common.file_chunker import chunk_file, get_chunk_targets, get_existing_chunks +from openpilot.common.transformations.camera import _ar_ox_fisheye, _os_fisheye +from openpilot.common.transformations.model import MEDMODEL_INPUT_SIZE, DM_INPUT_SIZE +from openpilot.selfdrive.modeld.constants import ModelConstants +from openpilot.selfdrive.modeld.helpers import TG_INPUT_DEVICES_PATH, usbgpu_present, modeld_pkl_path + + +CAMERA_CONFIGS = [ + (_ar_ox_fisheye.width, _ar_ox_fisheye.height), # tici: 1928x1208 + (_os_fisheye.width, _os_fisheye.height), # mici: 1344x760 +] Import('env', 'arch') chunker_file = File("#common/file_chunker.py") @@ -16,73 +26,116 @@ tinygrad_files = ["#"+x for x in glob.glob(env.Dir("#tinygrad_repo").relpath + " def estimate_pickle_max_size(onnx_size): return 1.2 * onnx_size + 10 * 1024 * 1024 # 20% + 10MB is plenty -# THREADS=0 is need to prevent bug: https://github.com/tinygrad/tinygrad/issues/14689 # get fastest TG config -available = set(Device.get_available_devices()) -# FIXME-SP: reset when we bump tg -if False: # 'CUDA' in available: +# probe in subprocess so usbgpu locks gets released on process exit +def probe_devices(): + return set(subprocess.run( + [sys.executable, '-c', 'from tinygrad import Device\nprint("\\n".join(Device.get_available_devices()))'], + capture_output=True, text=True, check=True).stdout.strip().splitlines()) + +available = probe_devices() +if 'CUDA' in available: tg_backend = 'CUDA' tg_flags = f'DEV={tg_backend}' elif 'QCOM' in available: tg_backend = 'QCOM' - tg_flags = f'DEV={tg_backend} FLOAT16=1 NOLOCALS=1 JIT_BATCH_SIZE=0' + tg_flags = f'DEV={tg_backend} IMAGE=1 FLOAT16=1 NOLOCALS=1 JIT_BATCH_SIZE=0 OPENPILOT_HACKS=1' else: - tg_backend = 'CPU' if arch == 'Darwin' else 'CPU CPU_LLVM=1' # FIXME-SP: reset when we bump tg - tg_flags = f'DEV={tg_backend} THREADS=0' + tg_backend = 'CPU' + tg_flags = f'DEV=CPU' if arch == 'Darwin' else 'DEV=CPU:LLVM' -def write_tg_compiled_flags(target, source, env): +tg_devices = { # which device to put jit inputs to at runtime + 'selfdrive.modeld.modeld': { + 'default': {'WARP_DEV': tg_backend, 'QUEUE_DEV': tg_backend}, + 'usbgpu': {'WARP_DEV': tg_backend, 'QUEUE_DEV': 'AMD'} + }, + 'selfdrive.modeld.dmonitoringmodeld': { + 'default': {'DEV': tg_backend} + }, +} + +USBGPU = usbgpu_present() # or release # TODO always build big model on release +if USBGPU: + usbgpu_tg_flags = f'DEBUG=2 DEV=USB+AMD:LLVM WARP_DEV={tg_backend} FLOAT16=1 JIT_BATCH_SIZE=0 GMMU=0' + # the USB+AMD GPU takes an exclusive flock; serialize all targets that touch it + usbgpu_lock = File("models/.usb_gpu.lock").abspath + +def write_tg_devices(target, source, env): with open(str(target[0]), "w") as f: - json.dump({"DEV": tg_backend}, f) + json.dump(tg_devices, f) f.write("\n") -compiled_flags_node = lenv.Command( - File("models/tg_compiled_flags.json").abspath, - tinygrad_files + [Value(tg_backend)], - write_tg_compiled_flags, +tg_devices_node = lenv.Command( + str(TG_INPUT_DEVICES_PATH), + [Value(tg_devices)], + write_tg_devices, ) # tinygrad calls brew which needs a $HOME in the env mac_brew_string = f'HOME={os.path.expanduser("~")}' if arch == 'Darwin' else '' -# Get model metadata -for model_name in ['driving_vision', 'driving_policy', 'dmonitoring_model']: - fn = File(f"models/{model_name}").abspath - script_files = [File(Dir("#selfdrive/modeld").File("get_model_metadata.py").abspath)] - cmd = f'{tg_flags} {mac_brew_string} python3 {Dir("#selfdrive/modeld").abspath}/get_model_metadata.py {fn}.onnx' - lenv.Command(fn + "_metadata.pkl", [fn + ".onnx"] + tinygrad_files + script_files + [compiled_flags_node], cmd) +modeld_dir = Dir("#selfdrive/modeld").abspath +compile_modeld_script = [ + File(f"{modeld_dir}/compile_modeld.py"), + File(f"{modeld_dir}/get_model_metadata.py"), + File("#system/camerad/cameras/nv12_info.py"), + File("#system/hardware/hw.py"), +] +model_w, model_h = MEDMODEL_INPUT_SIZE +frame_skip = ModelConstants.MODEL_RUN_FREQ // ModelConstants.MODEL_CONTEXT_FREQ -image_flag = { - 'larch64': 'IMAGE=2', -}.get(arch, 'IMAGE=0') -script_files = [File(Dir("#selfdrive/modeld").File("compile_warp.py").abspath)] -compile_warp_cmd = f'{tg_flags} {mac_brew_string} python3 {Dir("#selfdrive/modeld").abspath}/compile_warp.py ' -from openpilot.common.transformations.camera import _ar_ox_fisheye, _os_fisheye -warp_targets = [] -for cam in [_ar_ox_fisheye, _os_fisheye]: - w, h = cam.width, cam.height - warp_targets += [File(f"models/warp_{w}x{h}_tinygrad.pkl").abspath, File(f"models/dm_warp_{w}x{h}_tinygrad.pkl").abspath] -lenv.Command(warp_targets, tinygrad_files + script_files + [compiled_flags_node], compile_warp_cmd) +for usbgpu in [False, True] if USBGPU else [False]: + target_pkl_path = File(modeld_pkl_path(usbgpu)).abspath + file_prefix, cmd_flags = ('big_', usbgpu_tg_flags) if usbgpu else ('', tg_flags) + driving_onnx_deps = [p for m in [f'{file_prefix}driving_vision', f'{file_prefix}driving_on_policy'] + for p in get_existing_chunks(File(f"models/{m}.onnx").abspath)] + camera_res_args = ' '.join(f'{cw}x{ch}' for cw, ch in CAMERA_CONFIGS) + cmd = (f'{cmd_flags} {mac_brew_string} python3 {modeld_dir}/compile_modeld.py ' + f'--model-size {model_w}x{model_h} ' + f'--camera-resolutions {camera_res_args} ' + f'--vision-onnx {File(f"models/{file_prefix}driving_vision.onnx").abspath} ' + f'--on-policy-onnx {File(f"models/{file_prefix}driving_on_policy.onnx").abspath} ' + f'--output {target_pkl_path} --frame-skip {frame_skip}') + onnx_sizes_sum = sum(os.path.getsize(f) for f in driving_onnx_deps) + chunk_targets = get_chunk_targets(target_pkl_path, estimate_pickle_max_size(onnx_sizes_sum)) + def do_chunk(target, source, env, pkl=target_pkl_path, chunks=chunk_targets): + chunk_file(pkl, chunks) + node = lenv.Command( + chunk_targets, + tinygrad_files + compile_modeld_script + driving_onnx_deps + [Value(chunk_targets), chunker_file], + [cmd, Action(do_chunk, " [CHUNK] $TARGET")], + ) + if usbgpu: + lenv.SideEffect(usbgpu_lock, node) + +# get model metadata +fn = File(f"models/dmonitoring_model").abspath +script_files = [File(Dir("#selfdrive/modeld").File("get_model_metadata.py").abspath)] +cmd = f'{tg_flags} {mac_brew_string} python3 {Dir("#selfdrive/modeld").abspath}/get_model_metadata.py {fn}.onnx' +lenv.Command(fn + "_metadata.pkl", [fn + ".onnx"] + tinygrad_files + script_files + [tg_devices_node], cmd) + +dm_w, dm_h = DM_INPUT_SIZE +compile_dm_warp_script = [File(f"{modeld_dir}/compile_dm_warp.py")] +for cam_w, cam_h in CAMERA_CONFIGS: + dm_pkl_path = File(f"models/dm_warp_{cam_w}x{cam_h}_tinygrad.pkl").abspath + cmd = (f'{tg_flags} {mac_brew_string} python3 {modeld_dir}/compile_dm_warp.py ' + f'--camera-resolution {cam_w}x{cam_h} --warp-to {dm_w}x{dm_h} ' + f'--output {dm_pkl_path}') + lenv.Command(dm_pkl_path, tinygrad_files + compile_dm_warp_script + compile_modeld_script + [tg_devices_node], cmd) def tg_compile(flags, model_name): pythonpath_string = 'PYTHONPATH="${PYTHONPATH}:' + env.Dir("#tinygrad_repo").abspath + '"' fn = File(f"models/{model_name}").abspath pkl = fn + "_tinygrad.pkl" onnx_path = fn + ".onnx" - chunk_targets = get_chunk_paths(pkl, estimate_pickle_max_size(os.path.getsize(onnx_path))) - compile_node = lenv.Command( - pkl, - [onnx_path] + tinygrad_files + [chunker_file, compiled_flags_node], - f'{pythonpath_string} {flags} {image_flag} python3 {Dir("#tinygrad_repo").abspath}/examples/openpilot/compile3.py {fn}.onnx {pkl}', - ) + chunk_targets = get_chunk_targets(pkl, estimate_pickle_max_size(os.path.getsize(onnx_path))) def do_chunk(target, source, env): chunk_file(pkl, chunk_targets) return lenv.Command( chunk_targets, - compile_node, - do_chunk, + [onnx_path] + tinygrad_files + [Value(chunk_targets), chunker_file, tg_devices_node], + [f'{pythonpath_string} {flags} python3 {Dir("#tinygrad_repo").abspath}/examples/openpilot/compile3.py {fn}.onnx {pkl}', + Action(do_chunk, " [CHUNK] $TARGET")], ) -# Compile small models -for model_name in ['driving_vision', 'driving_policy', 'dmonitoring_model']: - tg_compile(tg_flags, model_name) - +tg_compile(tg_flags, 'dmonitoring_model') diff --git a/selfdrive/modeld/compile_dm_warp.py b/selfdrive/modeld/compile_dm_warp.py new file mode 100755 index 0000000000..16e0d39fbb --- /dev/null +++ b/selfdrive/modeld/compile_dm_warp.py @@ -0,0 +1,56 @@ +#!/usr/bin/env python3 +import argparse +import pickle +import time + +from tinygrad.tensor import Tensor +from tinygrad.device import Device +from tinygrad.engine.jit import TinyJit + +from openpilot.system.camerad.cameras.nv12_info import get_nv12_info +from openpilot.selfdrive.modeld.compile_modeld import NV12Frame, warp_perspective_tinygrad, _parse_size + + +def make_warp_dm(nv12: NV12Frame, dm_w, dm_h): + cam_w, cam_h, stride, _, _, _ = nv12 + stride_pad = stride - cam_w + + def warp_dm(input_frame, M_inv): + M_inv = M_inv.to(Device.DEFAULT).realize() + return warp_perspective_tinygrad(input_frame[:cam_h*stride], M_inv, + (dm_w, dm_h), (cam_h, cam_w), stride_pad, border_fill_val=16).reshape(-1, dm_h * dm_w) # Y + return warp_dm + + +def compile_dm_warp(nv12: NV12Frame, dm_w, dm_h, pkl_path): + print(f"Compiling DM warp for {nv12.width}x{nv12.height} -> {dm_w}x{dm_h}...") + + warp_dm_jit = TinyJit(make_warp_dm(nv12, dm_w, dm_h), prune=True) + + for i in range(10): + frame = Tensor.randint(nv12.size, low=0, high=256, dtype='uint8').realize() + M_inv = Tensor(Tensor.randn(3, 3).mul(8).realize().numpy(), device='NPY') + Device.default.synchronize() + st = time.perf_counter() + warp_dm_jit(frame, M_inv).realize() + mt = time.perf_counter() + Device.default.synchronize() + et = time.perf_counter() + print(f" [{i+1}/10] enqueue {(mt-st)*1e3:6.2f} ms -- total {(et-st)*1e3:6.2f} ms") + + with open(pkl_path, "wb") as f: + pickle.dump(warp_dm_jit, f) + print(f" Saved to {pkl_path}") + + +if __name__ == "__main__": + p = argparse.ArgumentParser() + p.add_argument('--camera-resolution', type=_parse_size, required=True, help='camera resolution WxH') + p.add_argument('--warp-to', type=_parse_size, required=True, help='DM input WxH') + p.add_argument('--output', required=True) + args = p.parse_args() + + cam_w, cam_h = args.camera_resolution + nv12 = NV12Frame(cam_w, cam_h, *get_nv12_info(cam_w, cam_h)) + dm_w, dm_h = args.warp_to + compile_dm_warp(nv12, dm_w, dm_h, args.output) diff --git a/selfdrive/modeld/compile_modeld.py b/selfdrive/modeld/compile_modeld.py new file mode 100755 index 0000000000..2f91076ab7 --- /dev/null +++ b/selfdrive/modeld/compile_modeld.py @@ -0,0 +1,299 @@ +#!/usr/bin/env python3 +import argparse +import atexit +import os +import pickle +import time +from functools import partial +from collections import namedtuple, defaultdict + +import numpy as np + +def _patch_tinygrad_fetch_fw(): + import hashlib + import pathlib + import zstandard + from tinygrad import helpers + _orig = helpers.fetch_fw + def fetch_fw(path, name, sha256): + p = pathlib.Path(f"/lib/firmware/{path}/{name}.zst") + if p.is_file(): + blob = zstandard.ZstdDecompressor().stream_reader(p.read_bytes()).read() + if hashlib.sha256(blob).hexdigest() == sha256: + return blob + return _orig(path, name, sha256) + helpers.fetch_fw = fetch_fw +_patch_tinygrad_fetch_fw() + +from tinygrad.tensor import Tensor +from tinygrad.helpers import Context +from tinygrad.device import Device +from tinygrad.engine.jit import TinyJit + + +NV12Frame = namedtuple("NV12Frame", ['width', 'height', 'stride', 'y_height', 'uv_height', 'size']) +WARP_INPUTS = ['img_q', 'big_img_q', 'tfm', 'big_tfm'] +POLICY_INPUTS = ['feat_q', 'desire_q', 'desire', 'traffic_convention', 'action_t'] + +UV_SCALE_MATRIX = np.array([[0.5, 0, 0], [0, 0.5, 0], [0, 0, 1]], dtype=np.float32) +UV_SCALE_MATRIX_INV = np.linalg.inv(UV_SCALE_MATRIX) + +WARP_DEV = os.getenv('WARP_DEV') + + +def make_random_images(keys, shape, device=None): + return {k: Tensor.randint(shape, low=0, high=256, dtype='uint8', device=device).realize() for k in keys} + + +def warp_perspective_tinygrad(src_flat, M_inv, dst_shape, src_shape, stride_pad, border_fill_val=None): + w_dst, h_dst = dst_shape + h_src, w_src = src_shape + + x = Tensor.arange(w_dst, device=WARP_DEV).reshape(1, w_dst).expand(h_dst, w_dst).reshape(-1) + y = Tensor.arange(h_dst, device=WARP_DEV).reshape(h_dst, 1).expand(h_dst, w_dst).reshape(-1) + + # inline 3x3 matmul as elementwise to avoid reduce op (enables fusion with gather) + src_x = M_inv[0, 0] * x + M_inv[0, 1] * y + M_inv[0, 2] + src_y = M_inv[1, 0] * x + M_inv[1, 1] * y + M_inv[1, 2] + src_w = M_inv[2, 0] * x + M_inv[2, 1] * y + M_inv[2, 2] + + src_x = src_x / src_w + src_y = src_y / src_w + + x_round = Tensor.round(src_x) + y_round = Tensor.round(src_y) + x_nn_clipped = x_round.clip(0, w_src - 1).cast('int') + y_nn_clipped = y_round.clip(0, h_src - 1).cast('int') + idx = y_nn_clipped * (w_src + stride_pad) + x_nn_clipped + sampled = src_flat[idx] + + if border_fill_val is None: + return sampled + + in_bounds = ((x_round >= 0) & (x_round <= w_src - 1) & + (y_round >= 0) & (y_round <= h_src - 1)).cast(sampled.dtype) + return sampled * in_bounds + Tensor(border_fill_val, dtype=sampled.dtype) * (1 - in_bounds) + + +def frames_to_tensor(frames): + H = (frames.shape[0] * 2) // 3 + W = frames.shape[1] + in_img1 = Tensor.cat(frames[0:H:2, 0::2], + frames[1:H:2, 0::2], + frames[0:H:2, 1::2], + frames[1:H:2, 1::2], + frames[H:H+H//4].reshape((H//2, W//2)), + frames[H+H//4:H+H//2].reshape((H//2, W//2)), dim=0).reshape((6, H//2, W//2)) + return in_img1 + + +def make_frame_prepare(nv12: NV12Frame, model_w, model_h): + cam_w, cam_h, stride, y_height, uv_height, _ = nv12 + uv_offset = stride * y_height + stride_pad = stride - cam_w + + def frame_prepare_tinygrad(input_frame, M_inv): + # UV_SCALE @ M_inv @ UV_SCALE_INV simplifies to elementwise scaling + M_inv_uv = M_inv * Tensor([[1.0, 1.0, 0.5], [1.0, 1.0, 0.5], [2.0, 2.0, 1.0]], device=WARP_DEV) + # deinterleave NV12 UV plane (UVUV... -> separate U, V) + uv = input_frame[uv_offset:uv_offset + uv_height * stride].reshape(uv_height, stride) + with Context(SPLIT_REDUCEOP=0): + y = warp_perspective_tinygrad(input_frame[:cam_h*stride], + M_inv, (model_w, model_h), + (cam_h, cam_w), stride_pad).realize() + u = warp_perspective_tinygrad(uv[:cam_h//2, :cam_w:2].flatten(), + M_inv_uv, (model_w//2, model_h//2), + (cam_h//2, cam_w//2), 0).realize() + v = warp_perspective_tinygrad(uv[:cam_h//2, 1:cam_w:2].flatten(), + M_inv_uv, (model_w//2, model_h//2), + (cam_h//2, cam_w//2), 0).realize() + yuv = y.cat(u).cat(v).reshape((model_h * 3 // 2, model_w)) + tensor = frames_to_tensor(yuv) + return tensor + return frame_prepare_tinygrad + + +def make_input_queues(vision_input_shapes, policy_input_shapes, frame_skip, device): + img = vision_input_shapes['img'] # (1, 12, 128, 256) + n_frames = img[1] // 6 + img_buf_shape = (frame_skip * (n_frames - 1) + 1, 6, img[2], img[3]) + + fb = policy_input_shapes['features_buffer'] # (1, 25, 512) + dp = policy_input_shapes['desire_pulse'] # (1, 25, 8) + tc = policy_input_shapes['traffic_convention'] # (1, 2) + #TODO action_t is hardcoded to match tc for future compatibility + at = tc + + npy = { + 'desire': np.zeros(dp[2], dtype=np.float32), + 'traffic_convention': np.zeros(tc, dtype=np.float32), + 'tfm': np.zeros((3, 3), dtype=np.float32), + 'big_tfm': np.zeros((3, 3), dtype=np.float32), + 'action_t': np.zeros(at, dtype=np.float32), + } + input_queues = { + 'img_q': Tensor(np.zeros(img_buf_shape, dtype=np.uint8), device=device).contiguous().realize(), + 'big_img_q': Tensor(np.zeros(img_buf_shape, dtype=np.uint8), device=device).contiguous().realize(), + 'feat_q': Tensor(np.zeros((frame_skip * (fb[1] - 1) + 1, fb[0], fb[2]), dtype=np.float32), device=device).contiguous().realize(), + 'desire_q': Tensor(np.zeros((frame_skip * dp[1], dp[0], dp[2]), dtype=np.float32), device=device).contiguous().realize(), + **{k: Tensor(v, device='NPY').realize() for k, v in npy.items()}, + } + return input_queues, npy + + +def shift_and_sample(buf, new_val, sample_fn): + buf.assign(buf[1:].cat(new_val, dim=0).contiguous()) + return sample_fn(buf) + + +def sample_skip(buf, frame_skip): + return buf[::frame_skip].contiguous().flatten(0, 1).unsqueeze(0) + + +def sample_desire(buf, frame_skip): + return buf.reshape(-1, frame_skip, *buf.shape[1:]).max(1).flatten(0, 1).unsqueeze(0) + + +def make_warp(nv12, model_w, model_h, frame_skip): + frame_prepare = make_frame_prepare(nv12, model_w, model_h) + sample_skip_fn = partial(sample_skip, frame_skip=frame_skip) + + def warp_enqueue(img_q, big_img_q, tfm, big_tfm, frame, big_frame): + tfm = tfm.to(WARP_DEV) + big_tfm = big_tfm.to(WARP_DEV) + Tensor.realize(tfm, big_tfm) + + warped_frame = frame_prepare(frame, tfm).unsqueeze(0).to(Device.DEFAULT) + warped_big_frame = frame_prepare(big_frame, big_tfm).unsqueeze(0).to(Device.DEFAULT) + img = shift_and_sample(img_q, warped_frame, sample_skip_fn) + big_img = shift_and_sample(big_img_q, warped_big_frame, sample_skip_fn) + return img, big_img + return warp_enqueue + + +def make_run_policy(vision_runner, on_policy_runner, vision_features_slice, frame_skip): + sample_desire_fn = partial(sample_desire, frame_skip=frame_skip) + sample_skip_fn = partial(sample_skip, frame_skip=frame_skip) + + def run_policy(img, big_img, feat_q, desire_q, desire, traffic_convention, action_t): + desire = desire.to(Device.DEFAULT) + traffic_convention = traffic_convention.to(Device.DEFAULT) + action_t = action_t.to(Device.DEFAULT) + Tensor.realize(desire, traffic_convention, action_t) + desire_buf = shift_and_sample(desire_q, desire.reshape(1, 1, -1), sample_desire_fn) + vision_out = next(iter(vision_runner({'img': img, 'big_img': big_img}).values())).cast('float32') + + new_feat = vision_out[:, vision_features_slice].reshape(1, -1).unsqueeze(0) + feat_buf = shift_and_sample(feat_q, new_feat, sample_skip_fn) + + inputs = { + 'features_buffer': feat_buf, + 'desire_pulse': desire_buf, + 'traffic_convention': traffic_convention, + 'action_t': action_t, + } + on_policy_out = next(iter(on_policy_runner(inputs).values())).cast('float32') + #off_policy_out = next(iter(off_policy_runner(inputs).values())).cast('float32') + return vision_out, on_policy_out + + return run_policy + + +def compile_jit(jit, make_random_inputs, input_keys, frame_skip, vision_metadata, policy_metadata): + vision_input_shapes = vision_metadata['input_shapes'] + policy_input_shapes = policy_metadata['input_shapes'] + + SEED = 42 + def random_inputs_run(fn, seed, test_val=None, test_buffers=None, expect_match=True): + input_queues, npy = make_input_queues(vision_input_shapes, policy_input_shapes, frame_skip, Device.DEFAULT) + np.random.seed(seed) + Tensor.manual_seed(seed) + + testing = test_val is not None or test_buffers is not None + n_runs = 1 if testing else 3 + + for i in range(n_runs): + for v in npy.values(): + v[:] = np.random.randn(*v.shape).astype(v.dtype) + Device.default.synchronize() + random_inputs = make_random_inputs() + st = time.perf_counter() + outs = fn(**{k: input_queues[k] for k in input_keys}, **random_inputs) + mt = time.perf_counter() + Device.default.synchronize() + et = time.perf_counter() + print(f" [{i+1}/{n_runs}] enqueue {(mt-st)*1e3:6.2f} ms -- total {(et-st)*1e3:6.2f} ms") + + if i == 0: + val = [np.copy(v.numpy()) for v in outs] + buffers = [np.copy(v.numpy().copy()) for v in input_queues.values()] + + if test_val is not None: + match = all(np.array_equal(a, b) for a, b in zip(val, test_val, strict=True)) + assert match == expect_match, f"outputs {'differ from' if expect_match else 'match'} baseline (seed={seed})" + if test_buffers is not None: + match = all(np.array_equal(a, b) for a, b in zip(buffers, test_buffers, strict=True)) + assert match == expect_match, f"buffers {'differ from' if expect_match else 'match'} baseline (seed={seed})" + return val, buffers + + print('capture + replay') + test_val, test_buffers = random_inputs_run(jit, SEED) + print('pickle round trip') + jit = pickle.loads(pickle.dumps(jit)) + random_inputs_run(jit, SEED, test_val, test_buffers, expect_match=True) + random_inputs_run(jit, SEED+1, test_val, test_buffers, expect_match=False) + return jit + + +def _parse_size(s): + w, h = s.lower().split('x') + return int(w), int(h) + + +def read_file_chunked_to_shm(path): + from openpilot.common.file_chunker import read_file_chunked + from openpilot.system.hardware.hw import Paths + shm_path = os.path.join(Paths.shm_path(), os.path.basename(path)) + atexit.register(lambda: os.path.exists(shm_path) and os.remove(shm_path)) + with open(shm_path, 'wb') as f: + f.write(read_file_chunked(path)) + return shm_path + + +if __name__ == "__main__": + from tinygrad.nn.onnx import OnnxRunner + from openpilot.system.camerad.cameras.nv12_info import get_nv12_info + from openpilot.selfdrive.modeld.get_model_metadata import make_metadata_dict + p = argparse.ArgumentParser() + p.add_argument('--model-size', type=_parse_size, required=True, help='model input WxH') + p.add_argument('--camera-resolutions', type=_parse_size, nargs='+', required=True, + help='camera resolutions WxH (one or more)') + p.add_argument('--vision-onnx', required=True) + p.add_argument('--on-policy-onnx', required=True) + p.add_argument('--output', required=True) + p.add_argument('--frame-skip', type=int, required=True) + args = p.parse_args() + + out = defaultdict(dict) + vision_path, on_policy_path = read_file_chunked_to_shm(args.vision_onnx), read_file_chunked_to_shm(args.on_policy_onnx) + model_w, model_h = args.model_size + + vision_runner = OnnxRunner(vision_path) + on_policy_runner = OnnxRunner(on_policy_path) + vision_metadata, on_policy_metadata = make_metadata_dict(vision_path), make_metadata_dict(on_policy_path) + + run_policy_jit = TinyJit(make_run_policy(vision_runner, on_policy_runner, vision_metadata['output_slices']['hidden_state'], args.frame_skip), prune=True) + out['metadata']['vision'], out['metadata']['on_policy'] = vision_metadata, on_policy_metadata + + make_random_model_inputs = partial(make_random_images, keys=['img', 'big_img'], shape=vision_metadata['input_shapes']['img']) + out['run_policy'] = compile_jit(run_policy_jit, make_random_model_inputs, POLICY_INPUTS, args.frame_skip, vision_metadata, on_policy_metadata) + + for cam_w, cam_h in args.camera_resolutions: + nv12 = NV12Frame(cam_w, cam_h, *get_nv12_info(cam_w, cam_h)) + make_random_warp_inputs = partial(make_random_images, keys=['frame', 'big_frame'], shape=nv12.size, device=WARP_DEV) + warp_enqueue = TinyJit(make_warp(nv12, model_w, model_h, args.frame_skip), prune=True) + out[(cam_w,cam_h)] = compile_jit(warp_enqueue, make_random_warp_inputs, WARP_INPUTS, args.frame_skip, vision_metadata, on_policy_metadata) + + with open(args.output, "wb") as f: + pickle.dump(out, f) + print(f"Saved JITs to {args.output} ({os.path.getsize(args.output) / 1e6:.2f} MB)") diff --git a/selfdrive/modeld/constants.py b/selfdrive/modeld/constants.py index ff7e1d8600..0fb09262d0 100644 --- a/selfdrive/modeld/constants.py +++ b/selfdrive/modeld/constants.py @@ -38,6 +38,7 @@ class ModelConstants: LANE_LINES_WIDTH = 2 ROAD_EDGES_WIDTH = 2 PLAN_WIDTH = 15 + ACTION_WIDTH = 2 DESIRE_PRED_WIDTH = 8 LAT_PLANNER_SOLUTION_WIDTH = 4 DESIRED_CURV_WIDTH = 1 diff --git a/selfdrive/modeld/dmonitoringmodeld.py b/selfdrive/modeld/dmonitoringmodeld.py index 1d80cd910e..eaf423e7be 100755 --- a/selfdrive/modeld/dmonitoringmodeld.py +++ b/selfdrive/modeld/dmonitoringmodeld.py @@ -1,12 +1,6 @@ #!/usr/bin/env python3 import os -from openpilot.selfdrive.modeld.tinygrad_helpers import MODELS_DIR, set_tinygrad_backend_from_compiled_flags -set_tinygrad_backend_from_compiled_flags() - -# FIXME-SP: remove once we bump tg -from openpilot.system.hardware import TICI -os.environ['DEV'] = 'QCOM' if TICI else 'CPU' - +from openpilot.selfdrive.modeld.helpers import MODELS_DIR, get_tg_input_devices from tinygrad.tensor import Tensor import time import pickle @@ -28,11 +22,13 @@ SEND_RAW_PRED = os.getenv('SEND_RAW_PRED') MODEL_PKL_PATH = MODELS_DIR / 'dmonitoring_model_tinygrad.pkl' METADATA_PATH = MODELS_DIR / 'dmonitoring_model_metadata.pkl' + class ModelState: inputs: dict[str, np.ndarray] output: np.ndarray - def __init__(self): + def __init__(self, cam_w: int, cam_h: int): + self.DEV = get_tg_input_devices(PROCESS_NAME, usbgpu=False)['DEV'] with open(METADATA_PATH, 'rb') as f: model_metadata = pickle.load(f) self.input_shapes = model_metadata['input_shapes'] @@ -44,31 +40,27 @@ class ModelState: self.warp_inputs_np = {'transform': np.zeros((3,3), dtype=np.float32)} self.warp_inputs = {k: Tensor(v, device='NPY') for k,v in self.warp_inputs_np.items()} - self.frame_buf_params = None + self.frame_buf_params = get_nv12_info(cam_w, cam_h) self.tensor_inputs = {k: Tensor(v, device='NPY').realize() for k,v in self.numpy_inputs.items()} self._blob_cache : dict[int, Tensor] = {} - self.image_warp = None self.model_run = pickle.loads(read_file_chunked(str(MODEL_PKL_PATH))) + with open(MODELS_DIR / f'dm_warp_{cam_w}x{cam_h}_tinygrad.pkl', "rb") as f: + self.image_warp = pickle.load(f) def run(self, buf: VisionBuf, calib: np.ndarray, transform: np.ndarray) -> tuple[np.ndarray, float]: self.numpy_inputs['calib'][0,:] = calib t1 = time.perf_counter() - if self.image_warp is None: - self.frame_buf_params = get_nv12_info(buf.width, buf.height) - warp_path = MODELS_DIR / f'dm_warp_{buf.width}x{buf.height}_tinygrad.pkl' - with open(warp_path, "rb") as f: - self.image_warp = pickle.load(f) - ptr = buf.data.ctypes.data + ptr = np.frombuffer(buf.data, dtype=np.uint8).ctypes.data # There is a ringbuffer of imgs, just cache tensors pointing to all of them if ptr not in self._blob_cache: - self._blob_cache[ptr] = Tensor.from_blob(ptr, (self.frame_buf_params[3],), dtype='uint8') + self._blob_cache[ptr] = Tensor.from_blob(ptr, (self.frame_buf_params[3],), dtype='uint8', device=self.DEV) self.warp_inputs_np['transform'][:] = transform[:] - self.tensor_inputs['input_img'] = self.image_warp(self._blob_cache[ptr], self.warp_inputs['transform']).realize() + self.tensor_inputs['input_img'] = self.image_warp(self._blob_cache[ptr], self.warp_inputs['transform']) - output = self.model_run(**self.tensor_inputs).contiguous().realize().uop.base.buffer.numpy().flatten() + output = self.model_run(**self.tensor_inputs).numpy().flatten() t2 = time.perf_counter() return output, t2 - t1 @@ -83,7 +75,7 @@ def parse_model_output(model_output): face_descs = model_output[f'face_descs_{ds_suffix}'] parsed[f'face_descs_{ds_suffix}'] = face_descs[:, :-6] parsed[f'face_descs_{ds_suffix}_std'] = safe_exp(face_descs[:, -6:]) - for key in ['face_prob', 'left_eye_prob', 'right_eye_prob','left_blink_prob', 'right_blink_prob', 'sunglasses_prob', 'using_phone_prob']: + for key in ['face_prob', 'left_eye_prob', 'right_eye_prob','left_blink_prob', 'right_blink_prob', 'sunglasses_prob', 'using_phone_prob', 'sleep_prob']: parsed[f'{key}_{ds_suffix}'] = sigmoid(model_output[f'{key}_{ds_suffix}']) return parsed @@ -99,6 +91,7 @@ def fill_driver_data(msg, model_output, ds_suffix): msg.rightBlinkProb = model_output[f'right_blink_prob_{ds_suffix}'][0, 0].item() msg.sunglassesProb = model_output[f'sunglasses_prob_{ds_suffix}'][0, 0].item() msg.phoneProb = model_output[f'using_phone_prob_{ds_suffix}'][0, 0].item() + msg.sleepProb = model_output[f'sleep_prob_{ds_suffix}'][0, 0].item() def get_driverstate_packet(model_output, frame_id: int, location_ts: int, exec_time: float, gpu_exec_time: float): msg = messaging.new_message('driverStateV2', valid=True) @@ -116,9 +109,6 @@ def get_driverstate_packet(model_output, frame_id: int, location_ts: int, exec_t def main(): config_realtime_process(7, 5) - model = ModelState() - cloudlog.warning("models loaded, dmonitoringmodeld starting") - cloudlog.warning("connecting to driver stream") vipc_client = VisionIpcClient("camerad", VisionStreamType.VISION_STREAM_DRIVER, True) while not vipc_client.connect(False): @@ -126,6 +116,9 @@ def main(): assert vipc_client.is_connected() cloudlog.warning(f"connected with buffer size: {vipc_client.buffer_len}") + model = ModelState(vipc_client.width, vipc_client.height) + cloudlog.warning("models loaded, dmonitoringmodeld starting") + sm = SubMaster(["liveCalibration"]) pm = PubMaster(["driverStateV2"]) diff --git a/selfdrive/modeld/get_model_metadata.py b/selfdrive/modeld/get_model_metadata.py index 838b1e9f40..e4c173957a 100755 --- a/selfdrive/modeld/get_model_metadata.py +++ b/selfdrive/modeld/get_model_metadata.py @@ -35,21 +35,21 @@ def get_metadata_value_by_name(model: dict[str, Any], name: str) -> str | Any: return None -if __name__ == "__main__": - model_path = pathlib.Path(sys.argv[1]) +def make_metadata_dict(model_path): model = MetadataOnnxPBParser(model_path).parse() output_slices = get_metadata_value_by_name(model, 'output_slices') assert output_slices is not None, 'output_slices not found in metadata' - - metadata = { + return { 'model_checkpoint': get_metadata_value_by_name(model, 'model_checkpoint'), 'output_slices': pickle.loads(codecs.decode(output_slices.encode(), "base64")), 'input_shapes': dict(get_name_and_shape(x) for x in model["graph"]["input"]), 'output_shapes': dict(get_name_and_shape(x) for x in model["graph"]["output"]), } + +if __name__ == "__main__": + model_path = pathlib.Path(sys.argv[1]) metadata_path = model_path.parent / (model_path.stem + '_metadata.pkl') with open(metadata_path, 'wb') as f: - pickle.dump(metadata, f) - + pickle.dump(make_metadata_dict(model_path), f) print(f'saved metadata to {metadata_path}') diff --git a/selfdrive/modeld/helpers.py b/selfdrive/modeld/helpers.py new file mode 100644 index 0000000000..64bf28873f --- /dev/null +++ b/selfdrive/modeld/helpers.py @@ -0,0 +1,26 @@ +import json +from pathlib import Path + +MODELS_DIR = Path(__file__).resolve().parent / 'models' +TG_INPUT_DEVICES_PATH = MODELS_DIR / 'tg_input_devices.json' +USBGPU_VID = 0xADD1 +USBGPU_PID = 0x0001 + + +def get_tg_input_devices(process_name: str, usbgpu: bool): + with open(TG_INPUT_DEVICES_PATH) as f: + return json.load(f)[process_name]['default' if not usbgpu else 'usbgpu'] + +def modeld_pkl_path(usbgpu: bool): + prefix = 'big_' if usbgpu else '' + return MODELS_DIR / f'{prefix}driving_tinygrad.pkl' + +def usbgpu_present() -> bool: + for d in Path("/sys/bus/usb/devices").glob("*"): + try: + if int((d / "idVendor").read_text(), 16) == USBGPU_VID and \ + int((d / "idProduct").read_text(), 16) == USBGPU_PID: + return True + except Exception: + pass + return False diff --git a/selfdrive/modeld/modeld.py b/selfdrive/modeld/modeld.py index 4f89058d70..9107cc6228 100755 --- a/selfdrive/modeld/modeld.py +++ b/selfdrive/modeld/modeld.py @@ -1,16 +1,6 @@ #!/usr/bin/env python3 import os -from openpilot.selfdrive.modeld.tinygrad_helpers import MODELS_DIR, set_tinygrad_backend_from_compiled_flags -set_tinygrad_backend_from_compiled_flags() - -# FIXME-SP: remove once we bump tg -from openpilot.system.hardware import TICI -os.environ['DEV'] = 'QCOM' if TICI else 'CPU' - -USBGPU = "USBGPU" in os.environ -if USBGPU: - os.environ['DEV'] = 'AMD' - os.environ['AMD_IFACE'] = 'USB' +os.environ['GMMU'] = '0' # for usbgpu fast loading, noop for qcom from tinygrad.tensor import Tensor import time import pickle @@ -30,52 +20,50 @@ from openpilot.common.transformations.model import get_warp_matrix from openpilot.selfdrive.controls.lib.desire_helper import DesireHelper from openpilot.selfdrive.controls.lib.drive_helpers import get_accel_from_plan, smooth_value, get_curvature_from_plan from openpilot.selfdrive.modeld.parse_model_outputs import Parser +from openpilot.selfdrive.modeld.compile_modeld import make_input_queues, WARP_INPUTS, POLICY_INPUTS from openpilot.selfdrive.modeld.fill_model_msg import fill_model_msg, fill_pose_msg, PublishState -from openpilot.common.file_chunker import read_file_chunked +from openpilot.common.file_chunker import read_file_chunked, get_manifest_path from openpilot.selfdrive.modeld.constants import ModelConstants, Plan +from openpilot.selfdrive.modeld.helpers import usbgpu_present, modeld_pkl_path, get_tg_input_devices from openpilot.sunnypilot.livedelay.helpers import get_lat_delay from openpilot.sunnypilot.modeld_v2.modeld_base import ModelStateBase - PROCESS_NAME = "selfdrive.modeld.modeld" SEND_RAW_PRED = os.getenv('SEND_RAW_PRED') -VISION_PKL_PATH = MODELS_DIR / 'driving_vision_tinygrad.pkl' -VISION_METADATA_PATH = MODELS_DIR / 'driving_vision_metadata.pkl' -POLICY_PKL_PATH = MODELS_DIR / 'driving_policy_tinygrad.pkl' -POLICY_METADATA_PATH = MODELS_DIR / 'driving_policy_metadata.pkl' - LAT_SMOOTH_SECONDS = 0.0 LONG_SMOOTH_SECONDS = 0.3 MIN_LAT_CONTROL_SPEED = 0.3 -IMG_QUEUE_SHAPE = (6*(ModelConstants.MODEL_RUN_FREQ//ModelConstants.MODEL_CONTEXT_FREQ + 1), 128, 256) -assert IMG_QUEUE_SHAPE[0] == 30 - 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: + if 'action' not in model_output: 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 = get_curvature_from_plan(plan[:,Plan.T_FROM_CURRENT_EULER][:,2], plan[:,Plan.ORIENTATION_RATE][:,2], ModelConstants.T_IDXS, v_ego, lat_action_t) - 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 + else: + desired_accel = model_output['action'][0,1] + desired_curvature = model_output['action'][0,0] / (max(1.0, v_ego))**2 + should_stop = (v_ego < 0.3 and desired_accel < 0.1) + desired_accel = smooth_value(desired_accel, prev_action.desiredAcceleration, LONG_SMOOTH_SECONDS) + 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)) - return log.ModelDataV2.Action(desiredCurvature=float(desired_curvature), - desiredAcceleration=float(desired_accel), - shouldStop=bool(should_stop)) class FrameMeta: frame_id: int = 0 @@ -86,175 +74,95 @@ class FrameMeta: if vipc is not None: self.frame_id, self.timestamp_sof, self.timestamp_eof = vipc.frame_id, vipc.timestamp_sof, vipc.timestamp_eof -class InputQueues: - def __init__ (self, model_fps, env_fps, n_frames_input): - assert env_fps % model_fps == 0 - assert env_fps >= model_fps - self.model_fps = model_fps - self.env_fps = env_fps - self.n_frames_input = n_frames_input - - self.dtypes = {} - self.shapes = {} - self.q = {} - - def update_dtypes_and_shapes(self, input_dtypes, input_shapes) -> None: - self.dtypes.update(input_dtypes) - if self.env_fps == self.model_fps: - self.shapes.update(input_shapes) - else: - for k in input_shapes: - shape = list(input_shapes[k]) - if 'img' in k: - n_channels = shape[1] // self.n_frames_input - shape[1] = (self.env_fps // self.model_fps + (self.n_frames_input - 1)) * n_channels - else: - shape[1] = (self.env_fps // self.model_fps) * shape[1] - self.shapes[k] = tuple(shape) - - def reset(self) -> None: - self.q = {k: np.zeros(self.shapes[k], dtype=self.dtypes[k]) for k in self.dtypes.keys()} - - def enqueue(self, inputs:dict[str, np.ndarray]) -> None: - for k in inputs.keys(): - if inputs[k].dtype != self.dtypes[k]: - raise ValueError(f'supplied input <{k}({inputs[k].dtype})> has wrong dtype, expected {self.dtypes[k]}') - input_shape = list(self.shapes[k]) - input_shape[1] = -1 - single_input = inputs[k].reshape(tuple(input_shape)) - sz = single_input.shape[1] - self.q[k][:,:-sz] = self.q[k][:,sz:] - self.q[k][:,-sz:] = single_input - - def get(self, *names) -> dict[str, np.ndarray]: - if self.env_fps == self.model_fps: - return {k: self.q[k] for k in names} - else: - out = {} - for k in names: - shape = self.shapes[k] - if 'img' in k: - n_channels = shape[1] // (self.env_fps // self.model_fps + (self.n_frames_input - 1)) - out[k] = np.concatenate([self.q[k][:, s:s+n_channels] for s in np.linspace(0, shape[1] - n_channels, self.n_frames_input, dtype=int)], axis=1) - elif 'pulse' in k: - # any pulse within interval counts - out[k] = self.q[k].reshape((shape[0], shape[1] * self.model_fps // self.env_fps, self.env_fps // self.model_fps, -1)).max(axis=2) - else: - idxs = np.arange(-1, -shape[1], -self.env_fps // self.model_fps)[::-1] - out[k] = self.q[k][:, idxs] - return out class ModelState(ModelStateBase): - inputs: dict[str, np.ndarray] - output: np.ndarray prev_desire: np.ndarray # for tracking the rising edge of the pulse - def __init__(self): + def __init__(self, cam_w: int, cam_h: int, usbgpu: bool): ModelStateBase.__init__(self) self.LAT_SMOOTH_SECONDS = LAT_SMOOTH_SECONDS - with open(VISION_METADATA_PATH, 'rb') as f: - vision_metadata = pickle.load(f) - self.vision_input_shapes = vision_metadata['input_shapes'] - self.vision_input_names = list(self.vision_input_shapes.keys()) - self.vision_output_slices = vision_metadata['output_slices'] - vision_output_size = vision_metadata['output_shapes']['outputs'][1] + input_devices = get_tg_input_devices(PROCESS_NAME, usbgpu) + self.WARP_DEV, self.QUEUE_DEV = input_devices['WARP_DEV'], input_devices['QUEUE_DEV'] + jits = pickle.loads(read_file_chunked(modeld_pkl_path(usbgpu))) + vision_metadata = jits['metadata']['vision'] + self.vision_input_shapes = vision_metadata['input_shapes'] + self.vision_input_names = list(self.vision_input_shapes.keys()) + self.vision_output_slices = vision_metadata['output_slices'] - with open(POLICY_METADATA_PATH, 'rb') as f: - policy_metadata = pickle.load(f) - self.policy_input_shapes = policy_metadata['input_shapes'] - self.policy_output_slices = policy_metadata['output_slices'] - policy_output_size = policy_metadata['output_shapes']['outputs'][1] + policy_metadata = jits['metadata']['on_policy'] + self.policy_input_shapes = policy_metadata['input_shapes'] + self.policy_output_slices = policy_metadata['output_slices'] self.prev_desire = np.zeros(ModelConstants.DESIRE_LEN, dtype=np.float32) - # policy inputs - self.numpy_inputs = {k: np.zeros(self.policy_input_shapes[k], dtype=np.float32) for k in self.policy_input_shapes} - self.full_input_queues = InputQueues(ModelConstants.MODEL_CONTEXT_FREQ, ModelConstants.MODEL_RUN_FREQ, ModelConstants.N_FRAMES) - for k in ['desire_pulse', 'features_buffer']: - self.full_input_queues.update_dtypes_and_shapes({k: self.numpy_inputs[k].dtype}, {k: self.numpy_inputs[k].shape}) - self.full_input_queues.reset() - - self.img_queues = {'img': Tensor.zeros(IMG_QUEUE_SHAPE, dtype='uint8').contiguous().realize(), - 'big_img': Tensor.zeros(IMG_QUEUE_SHAPE, dtype='uint8').contiguous().realize()} - self.full_frames : dict[str, Tensor] = {} - self._blob_cache : dict[int, Tensor] = {} - self.transforms_np = {k: np.zeros((3,3), dtype=np.float32) for k in self.img_queues} - self.transforms = {k: Tensor(v, device='NPY').realize() for k, v in self.transforms_np.items()} - self.vision_output = np.zeros(vision_output_size, dtype=np.float32) - self.policy_inputs = {k: Tensor(v, device='NPY').realize() for k,v in self.numpy_inputs.items()} - self.policy_output = np.zeros(policy_output_size, dtype=np.float32) + self.frame_skip = ModelConstants.MODEL_RUN_FREQ // ModelConstants.MODEL_CONTEXT_FREQ + self.input_queues, self.npy = make_input_queues(self.vision_input_shapes, self.policy_input_shapes, self.frame_skip, device=self.QUEUE_DEV) + self.full_frames: dict[str, Tensor] = {} + self._blob_cache: dict[int, Tensor] = {} self.parser = Parser() - self.frame_buf_params : dict[str, tuple[int, int, int, int]] = {} - self.update_imgs = None - self.vision_run = pickle.loads(read_file_chunked(str(VISION_PKL_PATH))) - self.policy_run = pickle.loads(read_file_chunked(str(POLICY_PKL_PATH))) + self.frame_buf_params = {k: get_nv12_info(cam_w, cam_h) for k in ('img', 'big_img')} + self.run_policy = jits['run_policy'] + self.warp_enqueue = jits[(cam_w,cam_h)] def slice_outputs(self, model_outputs: np.ndarray, output_slices: dict[str, slice]) -> dict[str, np.ndarray]: parsed_model_outputs = {k: model_outputs[np.newaxis, v] for k,v in output_slices.items()} return parsed_model_outputs def run(self, bufs: dict[str, VisionBuf], transforms: dict[str, np.ndarray], - inputs: dict[str, np.ndarray], prepare_only: bool) -> dict[str, np.ndarray] | None: - # Model decides when action is completed, so desire input is just a pulse triggered on rising edge - inputs['desire_pulse'][0] = 0 - new_desire = np.where(inputs['desire_pulse'] - self.prev_desire > .99, inputs['desire_pulse'], 0) - self.prev_desire[:] = inputs['desire_pulse'] - if self.update_imgs is None: - for key in bufs.keys(): - w, h = bufs[key].width, bufs[key].height - self.frame_buf_params[key] = get_nv12_info(w, h) - warp_path = MODELS_DIR / f'warp_{w}x{h}_tinygrad.pkl' - with open(warp_path, "rb") as f: - self.update_imgs = pickle.load(f) - + inputs: dict[str, np.ndarray], prepare_only: bool) -> dict[str, np.ndarray] | None: for key in bufs.keys(): - ptr = bufs[key].data.ctypes.data + ptr = np.frombuffer(bufs[key].data, dtype=np.uint8).ctypes.data yuv_size = self.frame_buf_params[key][3] # There is a ringbuffer of imgs, just cache tensors pointing to all of them cache_key = (key, ptr) if cache_key not in self._blob_cache: - self._blob_cache[cache_key] = Tensor.from_blob(ptr, (yuv_size,), dtype='uint8') + self._blob_cache[cache_key] = Tensor.from_blob(ptr, (yuv_size,), dtype='uint8', device=self.WARP_DEV) self.full_frames[key] = self._blob_cache[cache_key] - for key in bufs.keys(): - self.transforms_np[key][:,:] = transforms[key][:,:] - out = self.update_imgs(self.img_queues['img'], self.full_frames['img'], self.transforms['img'], - self.img_queues['big_img'], self.full_frames['big_img'], self.transforms['big_img']) - vision_inputs = {'img': out[0], 'big_img': out[1]} + # Model decides when action is completed, so desire input is just a pulse triggered on rising edge + inputs['desire_pulse'][0] = 0 + self.npy['desire'][:] = np.where(inputs['desire_pulse'] - self.prev_desire > .99, inputs['desire_pulse'], 0) + self.prev_desire[:] = inputs['desire_pulse'] + self.npy['traffic_convention'][:] = inputs['traffic_convention'] + self.npy['action_t'][:] = inputs['action_t'] + self.npy['tfm'][:,:] = transforms['img'][:,:] + self.npy['big_tfm'][:,:] = transforms['big_img'][:,:] + + img, big_img = self.warp_enqueue(**{k: self.input_queues[k] for k in WARP_INPUTS}, frame=self.full_frames['img'], big_frame=self.full_frames['big_img']) if prepare_only: return None - self.vision_output = self.vision_run(**vision_inputs).contiguous().realize().uop.base.buffer.numpy().flatten() - vision_outputs_dict = self.parser.parse_vision_outputs(self.slice_outputs(self.vision_output, self.vision_output_slices)) + vision_output, on_policy_output = self.run_policy( + **{k: self.input_queues[k] for k in POLICY_INPUTS}, img=img, big_img=big_img + ) - self.full_input_queues.enqueue({'features_buffer': vision_outputs_dict['hidden_state'], 'desire_pulse': new_desire}) - for k in ['desire_pulse', 'features_buffer']: - self.numpy_inputs[k][:] = self.full_input_queues.get(k)[k] - self.numpy_inputs['traffic_convention'][:] = inputs['traffic_convention'] - - self.policy_output = self.policy_run(**self.policy_inputs).contiguous().realize().uop.base.buffer.numpy().flatten() - policy_outputs_dict = self.parser.parse_policy_outputs(self.slice_outputs(self.policy_output, self.policy_output_slices)) + vision_output = vision_output.numpy().flatten() + on_policy_output = on_policy_output.numpy().flatten() + vision_outputs_dict = self.parser.parse_vision_outputs(self.slice_outputs(vision_output, self.vision_output_slices)) + policy_outputs_dict = self.parser.parse_policy_outputs(self.slice_outputs(on_policy_output, self.policy_output_slices)) combined_outputs_dict = {**vision_outputs_dict, **policy_outputs_dict} - if SEND_RAW_PRED: - combined_outputs_dict['raw_pred'] = np.concatenate([self.vision_output.copy(), self.policy_output.copy()]) + if SEND_RAW_PRED: + combined_outputs_dict['raw_pred'] = np.concatenate([vision_output.copy(), on_policy_output.copy()]) return combined_outputs_dict def main(demo=False): cloudlog.warning("modeld init") + _present = usbgpu_present() + _compiled = os.path.isfile(get_manifest_path(modeld_pkl_path(usbgpu=True))) + USBGPU = _present and _compiled + params = Params() + params.put_bool("UsbGpuPresent", _present) + params.put_bool("UsbGpuCompiled", _compiled) + 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("loading model") - model = ModelState() - cloudlog.warning(f"models loaded in {time.monotonic() - st:.1f}s, modeld starting") - # visionipc clients while True: available_streams = VisionIpcClient.available_streams("camerad", block=False) @@ -278,6 +186,11 @@ def main(demo=False): if use_extra_client: cloudlog.warning(f"connected extra cam with buffer size: {vipc_client_extra.buffer_len} ({vipc_client_extra.width} x {vipc_client_extra.height})") + st = time.monotonic() + cloudlog.warning("loading model") + model = ModelState(vipc_client_main.width, vipc_client_main.height, USBGPU) + cloudlog.warning(f"models loaded in {time.monotonic() - st:.1f}s, modeld starting") + # messaging pm = PubMaster(["modelV2", "drivingModelData", "cameraOdometry", "modelDataV2SP"]) sm = SubMaster(["deviceState", "carState", "roadCameraState", "liveCalibration", "driverMonitoringState", "carControl", "liveDelay"]) @@ -298,7 +211,6 @@ def main(demo=False): meta_main = FrameMeta() meta_extra = FrameMeta() - if demo: CP = get_demo_car_params() else: @@ -382,9 +294,14 @@ def main(demo=False): bufs = {name: buf_extra if 'big' in name else buf_main for name in model.vision_input_names} transforms = {name: model_transform_extra if 'big' in name else model_transform_main for name in model.vision_input_names} - inputs:dict[str, np.ndarray] = { + frame_delay = DT_MDL # compensate for time passed since the frame was captured: current_time - timestamp_eof is 50ms on average + action_delay = DT_MDL / 2 # middle of the interval between model output (current state) and next frame (expected state) + lat_action_t = lat_delay + frame_delay + action_delay + long_action_t = long_delay + frame_delay + action_delay + inputs: dict[str, np.ndarray] = { 'desire_pulse': vec_desire, 'traffic_convention': traffic_convention, + 'action_t': np.array([lat_action_t, long_action_t], dtype=np.float32), } mt1 = time.perf_counter() @@ -398,9 +315,7 @@ def main(demo=False): posenet_send = messaging.new_message('cameraOdometry') mdv2sp_send = messaging.new_message('modelDataV2SP') - frame_delay = DT_MDL # compensate for time passed since the frame was captured: current_time - timestamp_eof is 50ms on average - action_delay = DT_MDL / 2 # middle of the interval between model output (current state) and next frame (expected state) - action = get_action_from_model(model_output, prev_action, lat_delay + frame_delay + action_delay, long_delay + frame_delay + action_delay, v_ego) + action = get_action_from_model(model_output, prev_action, lat_action_t, long_action_t, 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, diff --git a/selfdrive/modeld/models/big_driving_on_policy.onnx b/selfdrive/modeld/models/big_driving_on_policy.onnx new file mode 100644 index 0000000000..f7b49c018a --- /dev/null +++ b/selfdrive/modeld/models/big_driving_on_policy.onnx @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:565e53c38dcd64c50dd3fe4d5ee1530213aeefd66c3f6b67ea6a72a32612a6bf +size 14061419 diff --git a/selfdrive/modeld/models/big_driving_policy.onnx b/selfdrive/modeld/models/big_driving_policy.onnx deleted file mode 120000 index e1b653a14a..0000000000 --- a/selfdrive/modeld/models/big_driving_policy.onnx +++ /dev/null @@ -1 +0,0 @@ -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 deleted file mode 120000 index 28ee71dd74..0000000000 --- a/selfdrive/modeld/models/big_driving_vision.onnx +++ /dev/null @@ -1 +0,0 @@ -driving_vision.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 100644 index 0000000000..d14f1969e0 --- /dev/null +++ b/selfdrive/modeld/models/big_driving_vision.onnx @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:1f0cab5033fe9e3bc5e174a2e790fa277f7d9fc44c65822d734064d2f899a9a0 +size 296203378 diff --git a/selfdrive/modeld/models/dmonitoring_model.onnx b/selfdrive/modeld/models/dmonitoring_model.onnx index dc621bed03..bd3f2c85a6 100644 --- a/selfdrive/modeld/models/dmonitoring_model.onnx +++ b/selfdrive/modeld/models/dmonitoring_model.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:7aff7ff1dc08bbaf562a8f77380ab5e5914f8557dba2f760d87e4d953f5604b0 -size 7307246 +oid sha256:3e7b31dfbc0a5234f1baf196513b77fc6af12204b8a8ffe8ee0417e48352f316 +size 7494962 diff --git a/selfdrive/modeld/models/driving_on_policy.onnx b/selfdrive/modeld/models/driving_on_policy.onnx new file mode 100644 index 0000000000..611ae9fe85 --- /dev/null +++ b/selfdrive/modeld/models/driving_on_policy.onnx @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:78477124cbf3ffe30fa951ebada8410b43c4242c6054584d656f1d329b067e15 +size 14060847 diff --git a/selfdrive/modeld/models/driving_policy.onnx b/selfdrive/modeld/models/driving_policy.onnx deleted file mode 100644 index 7c71bc9471..0000000000 --- a/selfdrive/modeld/models/driving_policy.onnx +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:853c6634746ff439a848349d00e4d5581cd941f13f7c1862c31b72a31cc24858 -size 14061595 diff --git a/selfdrive/modeld/models/driving_vision.onnx b/selfdrive/modeld/models/driving_vision.onnx index afd617667c..6c9fc4c84d 100644 --- a/selfdrive/modeld/models/driving_vision.onnx +++ b/selfdrive/modeld/models/driving_vision.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:940e9006a25f27f0b6e85da798e6a8fd1f6dd492dd7d0b9ff1a9436460f46129 -size 46887794 +oid sha256:ee29ee5bce84d1ce23e9ff381280de9b4e4d96d2934cd751740354884e112c66 +size 46877473 diff --git a/selfdrive/modeld/parse_model_outputs.py b/selfdrive/modeld/parse_model_outputs.py index a0b45d2a98..26c138b8ec 100644 --- a/selfdrive/modeld/parse_model_outputs.py +++ b/selfdrive/modeld/parse_model_outputs.py @@ -110,11 +110,7 @@ class Parser: return outs def parse_policy_outputs(self, outs: dict[str, np.ndarray]) -> dict[str, np.ndarray]: - plan_mhp = self.is_mhp(outs, 'plan', ModelConstants.IDX_N * ModelConstants.PLAN_WIDTH) - plan_in_N, plan_out_N = (ModelConstants.PLAN_MHP_N, ModelConstants.PLAN_MHP_SELECTION) if plan_mhp else (0, 0) - self.parse_mdn('plan', outs, in_N=plan_in_N, out_N=plan_out_N, out_shape=(ModelConstants.IDX_N, ModelConstants.PLAN_WIDTH)) - if 'planplus' in outs: - self.parse_mdn('planplus', outs, in_N=0, out_N=0, out_shape=(ModelConstants.IDX_N, ModelConstants.PLAN_WIDTH)) + self.parse_mdn('plan', outs, in_N=0, out_N=0, out_shape=(ModelConstants.IDX_N, ModelConstants.PLAN_WIDTH)) self.parse_categorical_crossentropy('desire_state', outs, out_shape=(ModelConstants.DESIRE_PRED_WIDTH,)) return outs diff --git a/selfdrive/modeld/tinygrad_helpers.py b/selfdrive/modeld/tinygrad_helpers.py deleted file mode 100644 index 49a6ed6161..0000000000 --- a/selfdrive/modeld/tinygrad_helpers.py +++ /dev/null @@ -1,12 +0,0 @@ -import json -import os -from pathlib import Path - -MODELS_DIR = Path(__file__).parent / 'models' -COMPILED_FLAGS_PATH = MODELS_DIR / 'tg_compiled_flags.json' - - -def set_tinygrad_backend_from_compiled_flags() -> None: - if os.path.isfile(COMPILED_FLAGS_PATH): - with open(COMPILED_FLAGS_PATH) as f: - os.environ['DEV'] = str(json.load(f)['DEV']) diff --git a/selfdrive/monitoring/README.md b/selfdrive/monitoring/README.md deleted file mode 100644 index 2a29ea06b5..0000000000 --- a/selfdrive/monitoring/README.md +++ /dev/null @@ -1,15 +0,0 @@ -# driver monitoring (DM) - -Uploading driver-facing camera footage is opt-in, but it is encouraged to opt-in to improve the DM model. You can always change your preference using the "Record and Upload Driver Camera" toggle. - -## Troubleshooting - -Before creating a bug report, go through these troubleshooting steps. - -* Ensure the driver-facing camera has a good view of the driver in normal driving positions. - * This can be checked in Settings -> Device -> Preview Driver Camera (when car is off). -* If the camera can't see the driver, the device should be re-mounted. - -## Bug report - -In order for us to look into DM bug reports, we'll need the driver-facing camera footage. If you don't normally have this enabled, simply enable the toggle for a single drive. Also ensure the "Upload Raw Logs" toggle is enabled before going for a drive. diff --git a/selfdrive/monitoring/dmonitoringd.py b/selfdrive/monitoring/dmonitoringd.py index 022415af6d..bedad967b6 100755 --- a/selfdrive/monitoring/dmonitoringd.py +++ b/selfdrive/monitoring/dmonitoringd.py @@ -2,7 +2,7 @@ import cereal.messaging as messaging from openpilot.common.params import Params from openpilot.common.realtime import config_realtime_process -from openpilot.selfdrive.monitoring.helpers import DriverMonitoring +from openpilot.selfdrive.monitoring.policy import DriverMonitoring def dmonitoringd_thread(): @@ -25,7 +25,7 @@ def dmonitoringd_thread(): valid = sm.all_checks() if demo_mode and sm.valid['driverStateV2']: - DM.run_step(sm, demo=demo_mode) + DM.run_step(sm, demo=True) elif valid: DM.run_step(sm, demo=demo_mode) @@ -40,9 +40,9 @@ def dmonitoringd_thread(): # save rhd virtual toggle every 5 mins if (sm['driverStateV2'].frameId % 6000 == 0 and not demo_mode and - DM.wheelpos.prob_offseter.filtered_stat.n > DM.settings._WHEELPOS_FILTER_MIN_COUNT and - DM.wheel_on_right == (DM.wheelpos.prob_offseter.filtered_stat.M > DM.settings._WHEELPOS_THRESHOLD)): - params.put_bool_nonblocking("IsRhdDetected", DM.wheel_on_right) + DM.wheelpos_offsetter.filtered_stat.n > DM.settings._WHEELPOS_FILTER_MIN_COUNT and + DM.wheel_on_right == (DM.wheelpos_offsetter.filtered_stat.M > DM.settings._WHEELPOS_THRESHOLD)): + params.put_bool("IsRhdDetected", DM.wheel_on_right) def main(): dmonitoringd_thread() diff --git a/selfdrive/monitoring/helpers.py b/selfdrive/monitoring/policy.py similarity index 50% rename from selfdrive/monitoring/helpers.py rename to selfdrive/monitoring/policy.py index b392182607..728d4881cd 100644 --- a/selfdrive/monitoring/helpers.py +++ b/selfdrive/monitoring/policy.py @@ -1,18 +1,20 @@ +from collections import defaultdict from math import atan2, radians import numpy as np from cereal import car, log import cereal.messaging as messaging -from openpilot.selfdrive.selfdrived.events import Events -from openpilot.selfdrive.selfdrived.alertmanager import set_offroad_alert from openpilot.common.realtime import DT_DMON from openpilot.common.filter_simple import FirstOrderFilter from openpilot.common.params import Params from openpilot.common.stat_live import RunningStatFilter from openpilot.common.transformations.camera import DEVICE_CAMERAS -from openpilot.system.hardware import HARDWARE -EventName = log.OnroadEvent.EventName +AlertLevel = log.DriverMonitoringState.AlertLevel +MonitoringPolicy = log.DriverMonitoringState.MonitoringPolicy + +def to_percent(v): + return int(min(max(v * 100., 0.), 100.)) # ****************************************************************************************** # NOTE: To fork maintainers. @@ -21,22 +23,27 @@ EventName = log.OnroadEvent.EventName # ****************************************************************************************** class DRIVER_MONITOR_SETTINGS: - def __init__(self, device_type): - self._DT_DMON = DT_DMON - # ref (page15-16): https://eur-lex.europa.eu/legal-content/EN/TXT/PDF/?uri=CELEX:42018X1947&rid=2 - self._AWARENESS_TIME = 30. # passive wheeltouch total timeout - self._AWARENESS_PRE_TIME_TILL_TERMINAL = 15. - self._AWARENESS_PROMPT_TIME_TILL_TERMINAL = 6. - self._DISTRACTED_TIME = 11. # active monitoring total timeout - self._DISTRACTED_PRE_TIME_TILL_TERMINAL = 8. - self._DISTRACTED_PROMPT_TIME_TILL_TERMINAL = 6. + def __init__(self): + # https://eur-lex.europa.eu/legal-content/EN/TXT/PDF/?uri=CELEX:42018X1947&rid=2 + self._WHEELTOUCH_POLICY_ALERT_1_TIMEOUT = 15. + self._WHEELTOUCH_POLICY_ALERT_2_TIMEOUT = 24. + self._WHEELTOUCH_POLICY_ALERT_3_TIMEOUT = 30. + # https://cdn.euroncap.com/cars/assets/euro_ncap_protocol_safe_driving_driver_engagement_v11_a30e874152.pdf + self._VISION_POLICY_ALERT_1_TIMEOUT = 3. + self._VISION_POLICY_ALERT_2_TIMEOUT = 5. + self._VISION_POLICY_ALERT_3_TIMEOUT = 11. + + self._TIMEOUT_RECOVERY_FACTOR_MAX = 5. + self._TIMEOUT_RECOVERY_FACTOR_MIN = 1.25 + + self._MAX_TERMINAL_ALERTS = 3 # not allowed to engage after 3 terminal alerts + self._MAX_TERMINAL_DURATION = int(30 / DT_DMON) # not allowed to engage after 30s of terminal alerts self._FACE_THRESHOLD = 0.7 self._EYE_THRESHOLD = 0.65 self._SG_THRESHOLD = 0.9 self._BLINK_THRESHOLD = 0.865 self._PHONE_THRESH = 0.5 - self._POSE_PITCH_THRESHOLD = 0.3133 self._POSE_PITCH_THRESHOLD_SLACK = 0.3237 self._POSE_PITCH_THRESHOLD_STRICT = self._POSE_PITCH_THRESHOLD @@ -57,106 +64,79 @@ class DRIVER_MONITOR_SETTINGS: self._YAW_MIN_OFFSET = -0.0246 self._DCAM_UNCERTAIN_ALERT_THRESHOLD = 0.1 - self._DCAM_UNCERTAIN_ALERT_COUNT = int(60 / self._DT_DMON) - self._DCAM_UNCERTAIN_RESET_COUNT = int(20 / self._DT_DMON) - self._POSESTD_THRESHOLD = 0.3 - self._HI_STD_FALLBACK_TIME = int(10 / self._DT_DMON) # fall back to wheel touch if model is uncertain for 10s + self._DCAM_UNCERTAIN_ALERT_COUNT = int(60 / DT_DMON) + self._DCAM_UNCERTAIN_RESET_COUNT = int(2 / DT_DMON) + self._HI_STD_THRESHOLD = 0.3 + self._HI_STD_FALLBACK_TIME = int(10 / DT_DMON) # fall back to wheel touch if model is uncertain for 10s self._DISTRACTED_FILTER_TS = 0.25 # 0.6Hz self._POSE_CALIB_MIN_SPEED = 13 # 30 mph - self._POSE_OFFSET_MIN_COUNT = int(60 / self._DT_DMON) # valid data counts before calibration completes, 1min cumulative - self._POSE_OFFSET_MAX_COUNT = int(360 / self._DT_DMON) # stop deweighting new data after 6 min, aka "short term memory" - + self._POSE_OFFSET_MIN_COUNT = int(60 / DT_DMON) # valid data counts before calibration completes, 1min cumulative + self._POSE_OFFSET_MAX_COUNT = int(360 / DT_DMON) # stop deweighting new data after 6 min, aka "short term memory" self._WHEELPOS_CALIB_MIN_SPEED = 11 self._WHEELPOS_THRESHOLD = 0.5 - self._WHEELPOS_FILTER_MIN_COUNT = int(15 / self._DT_DMON) # allow 15 seconds to converge wheel side + self._WHEELPOS_FILTER_MIN_COUNT = int(15 / DT_DMON) # allow 15 seconds to converge wheel side self._WHEELPOS_DATA_AVG = 0.03 self._WHEELPOS_DATA_VAR = 3*5.5e-5 self._WHEELPOS_MAX_COUNT = -1 - self._RECOVERY_FACTOR_MAX = 5. # relative to minus step change - self._RECOVERY_FACTOR_MIN = 1.25 # relative to minus step change - - self._MAX_TERMINAL_ALERTS = 3 # not allowed to engage after 3 terminal alerts - self._MAX_TERMINAL_DURATION = int(30 / self._DT_DMON) # not allowed to engage after 30s of terminal alerts - -class DistractedType: - - NOT_DISTRACTED = 0 - DISTRACTED_POSE = 1 << 0 - DISTRACTED_BLINK = 1 << 1 - DISTRACTED_PHONE = 1 << 2 - class DriverPose: def __init__(self, settings): pitch_filter_raw_priors = (settings._PITCH_NATURAL_OFFSET, settings._PITCH_NATURAL_VAR, 2) yaw_filter_raw_priors = (settings._YAW_NATURAL_OFFSET, settings._YAW_NATURAL_VAR, 2) self.yaw = 0. self.pitch = 0. - self.roll = 0. - self.yaw_std = 0. - self.pitch_std = 0. - self.roll_std = 0. - self.pitch_offseter = RunningStatFilter(raw_priors=pitch_filter_raw_priors, max_trackable=settings._POSE_OFFSET_MAX_COUNT) - self.yaw_offseter = RunningStatFilter(raw_priors=yaw_filter_raw_priors, max_trackable=settings._POSE_OFFSET_MAX_COUNT) + self.pitch_offsetter = RunningStatFilter(raw_priors=pitch_filter_raw_priors, max_trackable=settings._POSE_OFFSET_MAX_COUNT) + self.yaw_offsetter = RunningStatFilter(raw_priors=yaw_filter_raw_priors, max_trackable=settings._POSE_OFFSET_MAX_COUNT) self.calibrated = False self.low_std = True self.cfactor_pitch = 1. self.cfactor_yaw = 1. self.steer_yaw_offset = 0. -class DriverProb: - def __init__(self, raw_priors, max_trackable): - self.prob = 0. - self.prob_offseter = RunningStatFilter(raw_priors=raw_priors, max_trackable=max_trackable) - self.prob_calibrated = False - class DriverBlink: def __init__(self): self.left = 0. self.right = 0. - # model output refers to center of undistorted+leveled image -EFL = 598.0 # focal length in K -cam = DEVICE_CAMERAS[("tici", "ar0231")] # corrected image has same size as raw -W, H = (cam.dcam.width, cam.dcam.height) # corrected image has same size as raw +ref_undistorted_cam = DEVICE_CAMERAS[("tici", "ar0231")].dcam +dcam_undistorted_FL = 598.0 +dcam_undistorted_W, dcam_undistorted_H = (ref_undistorted_cam.width, ref_undistorted_cam.height) -def face_orientation_from_net(angles_desc, pos_desc, rpy_calib): - # the output of these angles are in device frame - # so from driver's perspective, pitch is up and yaw is right +def face_orientation_from_model(orient_model, pos_model, rpy_calib): + pitch_model = orient_model[0] + yaw_model = orient_model[1] - pitch_net, yaw_net, roll_net = angles_desc + face_pixel_position = ((pos_model[0]+0.5)*dcam_undistorted_W, (pos_model[1]+0.5)*dcam_undistorted_H) + yaw_focal_angle = atan2(face_pixel_position[0] - dcam_undistorted_W//2, dcam_undistorted_FL) + pitch_focal_angle = atan2(face_pixel_position[1] - dcam_undistorted_H//2, dcam_undistorted_FL) - face_pixel_position = ((pos_desc[0]+0.5)*W, (pos_desc[1]+0.5)*H) - yaw_focal_angle = atan2(face_pixel_position[0] - W//2, EFL) - pitch_focal_angle = atan2(face_pixel_position[1] - H//2, EFL) + pitch = pitch_model + pitch_focal_angle + yaw = -yaw_model + yaw_focal_angle - pitch = pitch_net + pitch_focal_angle - yaw = -yaw_net + yaw_focal_angle - - # no calib for roll pitch -= rpy_calib[1] yaw -= rpy_calib[2] - return roll_net, pitch, yaw + return pitch, yaw class DriverMonitoring: def __init__(self, rhd_saved=False, settings=None, always_on=False): # init policy settings - self.settings = settings if settings is not None else DRIVER_MONITOR_SETTINGS(device_type=HARDWARE.get_device_type()) + self.settings = settings if settings is not None else DRIVER_MONITOR_SETTINGS() # init driver status wheelpos_filter_raw_priors = (self.settings._WHEELPOS_DATA_AVG, self.settings._WHEELPOS_DATA_VAR, 2) - self.wheelpos = DriverProb(raw_priors=wheelpos_filter_raw_priors, max_trackable=self.settings._WHEELPOS_MAX_COUNT) + self.wheelpos_offsetter = RunningStatFilter(raw_priors=wheelpos_filter_raw_priors, max_trackable=self.settings._WHEELPOS_MAX_COUNT) self.pose = DriverPose(settings=self.settings) self.blink = DriverBlink() self.phone_prob = 0. + self.alert_level = AlertLevel.none self.always_on = always_on - self.distracted_types = [] + self.distracted_types = defaultdict(bool) self.driver_distracted = False - self.driver_distraction_filter = FirstOrderFilter(0., self.settings._DISTRACTED_FILTER_TS, self.settings._DT_DMON) + self.driver_distraction_filter = FirstOrderFilter(0., self.settings._DISTRACTED_FILTER_TS, DT_DMON) self.wheel_on_right = False self.wheel_on_right_last = None self.wheel_on_right_default = rhd_saved @@ -164,61 +144,56 @@ class DriverMonitoring: self.terminal_alert_cnt = 0 self.terminal_time = 0 self.step_change = 0. - self.active_monitoring_mode = True + self.active_policy = MonitoringPolicy.vision + self.driver_interacting = False self.is_model_uncertain = False self.hi_stds = 0 - self.threshold_pre = self.settings._DISTRACTED_PRE_TIME_TILL_TERMINAL / self.settings._DISTRACTED_TIME - self.threshold_prompt = self.settings._DISTRACTED_PROMPT_TIME_TILL_TERMINAL / self.settings._DISTRACTED_TIME + self.model_std_max = 0. + self.threshold_alert_1 = 0. + self.threshold_alert_2 = 0. self.dcam_uncertain_cnt = 0 - self.dcam_uncertain_alerted = False # once per drive self.dcam_reset_cnt = 0 - - self.params = Params() - self.too_distracted = self.params.get_bool("DriverTooDistracted") + self.too_distracted = Params().get_bool("DriverTooDistracted") self._reset_awareness() - self._set_timers(active_monitoring=True) - self._reset_events() + self._set_policy(MonitoringPolicy.vision) def _reset_awareness(self): self.awareness = 1. - self.awareness_active = 1. - self.awareness_passive = 1. + self.last_vision_awareness = 1. + self.last_wheeltouch_awareness = 1. - def _reset_events(self): - self.current_events = Events() - - def _set_timers(self, active_monitoring): - if self.active_monitoring_mode and self.awareness <= self.threshold_prompt: - if active_monitoring: - self.step_change = self.settings._DT_DMON / self.settings._DISTRACTED_TIME + def _set_policy(self, target_policy): + if self.active_policy == MonitoringPolicy.vision and self.awareness <= self.threshold_alert_2: + if target_policy == MonitoringPolicy.vision: + self.step_change = DT_DMON / self.settings._VISION_POLICY_ALERT_3_TIMEOUT else: self.step_change = 0. return # no exploit after orange alert elif self.awareness <= 0.: return - if active_monitoring: + if target_policy == MonitoringPolicy.vision: # when falling back from passive mode to active mode, reset awareness to avoid false alert - if not self.active_monitoring_mode: - self.awareness_passive = self.awareness - self.awareness = self.awareness_active + if self.active_policy != MonitoringPolicy.vision: + self.last_wheeltouch_awareness = self.awareness + self.awareness = self.last_vision_awareness - self.threshold_pre = self.settings._DISTRACTED_PRE_TIME_TILL_TERMINAL / self.settings._DISTRACTED_TIME - self.threshold_prompt = self.settings._DISTRACTED_PROMPT_TIME_TILL_TERMINAL / self.settings._DISTRACTED_TIME - self.step_change = self.settings._DT_DMON / self.settings._DISTRACTED_TIME - self.active_monitoring_mode = True + self.threshold_alert_1 = 1. - self.settings._VISION_POLICY_ALERT_1_TIMEOUT / self.settings._VISION_POLICY_ALERT_3_TIMEOUT + self.threshold_alert_2 = 1. - self.settings._VISION_POLICY_ALERT_2_TIMEOUT / self.settings._VISION_POLICY_ALERT_3_TIMEOUT + self.step_change = DT_DMON / self.settings._VISION_POLICY_ALERT_3_TIMEOUT + self.active_policy = MonitoringPolicy.vision else: - if self.active_monitoring_mode: - self.awareness_active = self.awareness - self.awareness = self.awareness_passive + if self.active_policy == MonitoringPolicy.vision: + self.last_vision_awareness = self.awareness + self.awareness = self.last_wheeltouch_awareness - self.threshold_pre = self.settings._AWARENESS_PRE_TIME_TILL_TERMINAL / self.settings._AWARENESS_TIME - self.threshold_prompt = self.settings._AWARENESS_PROMPT_TIME_TILL_TERMINAL / self.settings._AWARENESS_TIME - self.step_change = self.settings._DT_DMON / self.settings._AWARENESS_TIME - self.active_monitoring_mode = False + self.threshold_alert_1 = 1. - self.settings._WHEELTOUCH_POLICY_ALERT_1_TIMEOUT / self.settings._WHEELTOUCH_POLICY_ALERT_3_TIMEOUT + self.threshold_alert_2 = 1. - self.settings._WHEELTOUCH_POLICY_ALERT_2_TIMEOUT / self.settings._WHEELTOUCH_POLICY_ALERT_3_TIMEOUT + self.step_change = DT_DMON / self.settings._WHEELTOUCH_POLICY_ALERT_3_TIMEOUT + self.active_policy = MonitoringPolicy.wheeltouch - def _set_policy(self, brake_disengage_prob, car_speed): + def _set_pose_strictness(self, brake_disengage_prob, car_speed): bp = brake_disengage_prob k1 = max(-0.00156*((car_speed-16)**2)+0.6, 0.2) bp_normal = max(min(bp / k1, 0.5),0) @@ -230,15 +205,15 @@ class DriverMonitoring: self.settings._POSE_YAW_THRESHOLD_STRICT]) / self.settings._POSE_YAW_THRESHOLD def _get_distracted_types(self): - distracted_types = [] + self.distracted_types = defaultdict(bool) if not self.pose.calibrated: pitch_error = self.pose.pitch - self.settings._PITCH_NATURAL_OFFSET yaw_error = self.pose.yaw - self.settings._YAW_NATURAL_OFFSET else: - pitch_error = self.pose.pitch - min(max(self.pose.pitch_offseter.filtered_stat.mean(), + pitch_error = self.pose.pitch - min(max(self.pose.pitch_offsetter.filtered_stat.mean(), self.settings._PITCH_MIN_OFFSET), self.settings._PITCH_MAX_OFFSET) - yaw_error = self.pose.yaw - min(max(self.pose.yaw_offseter.filtered_stat.mean(), + yaw_error = self.pose.yaw - min(max(self.pose.yaw_offsetter.filtered_stat.mean(), self.settings._YAW_MIN_OFFSET), self.settings._YAW_MAX_OFFSET) pitch_error = 0 if pitch_error > 0 else abs(pitch_error) # no positive pitch limit @@ -250,28 +225,21 @@ class DriverMonitoring: pitch_threshold = self.settings._POSE_PITCH_THRESHOLD * self.pose.cfactor_pitch if self.pose.calibrated else self.settings._PITCH_NATURAL_THRESHOLD yaw_threshold = self.settings._POSE_YAW_THRESHOLD * self.pose.cfactor_yaw - if pitch_error > pitch_threshold or yaw_error > yaw_threshold: - distracted_types.append(DistractedType.DISTRACTED_POSE) - - if (self.blink.left + self.blink.right)*0.5 > self.settings._BLINK_THRESHOLD: - distracted_types.append(DistractedType.DISTRACTED_BLINK) - - if self.phone_prob > self.settings._PHONE_THRESH: - distracted_types.append(DistractedType.DISTRACTED_PHONE) - - return distracted_types + self.distracted_types['pose'] = bool((pitch_error > pitch_threshold) or (yaw_error > yaw_threshold)) + self.distracted_types['eye'] = bool((self.blink.left + self.blink.right)*0.5 > self.settings._BLINK_THRESHOLD) + self.distracted_types['phone'] = bool(self.phone_prob > self.settings._PHONE_THRESH) def _update_states(self, driver_state, cal_rpy, car_speed, op_engaged, standstill, demo_mode=False, steering_angle_deg=0.): rhd_pred = driver_state.wheelOnRightProb # calibrates only when there's movement and either face detected if car_speed > self.settings._WHEELPOS_CALIB_MIN_SPEED and (driver_state.leftDriverData.faceProb > self.settings._FACE_THRESHOLD or driver_state.rightDriverData.faceProb > self.settings._FACE_THRESHOLD): - self.wheelpos.prob_offseter.push_and_update(rhd_pred) + self.wheelpos_offsetter.push_and_update(rhd_pred) - self.wheelpos.prob_calibrated = self.wheelpos.prob_offseter.filtered_stat.n > self.settings._WHEELPOS_FILTER_MIN_COUNT + wheelpos_calibrated = self.wheelpos_offsetter.filtered_stat.n >= self.settings._WHEELPOS_FILTER_MIN_COUNT - if self.wheelpos.prob_calibrated or demo_mode: - self.wheel_on_right = self.wheelpos.prob_offseter.filtered_stat.M > self.settings._WHEELPOS_THRESHOLD + if wheelpos_calibrated or demo_mode: + self.wheel_on_right = self.wheelpos_offsetter.filtered_stat.M > self.settings._WHEELPOS_THRESHOLD else: self.wheel_on_right = self.wheel_on_right_default # use default/saved if calibration is unfinished # make sure no switching when engaged @@ -283,71 +251,60 @@ class DriverMonitoring: return self.face_detected = driver_data.faceProb > self.settings._FACE_THRESHOLD - self.pose.roll, self.pose.pitch, self.pose.yaw = face_orientation_from_net(driver_data.faceOrientation, driver_data.facePosition, cal_rpy) + self.pose.pitch, self.pose.yaw = face_orientation_from_model(driver_data.faceOrientation, driver_data.facePosition, cal_rpy) steer_d = max(abs(steering_angle_deg) - self.settings._POSE_YAW_MIN_STEER_DEG, 0.) self.pose.steer_yaw_offset = radians(steer_d) * -np.sign(steering_angle_deg) * self.settings._POSE_YAW_STEER_FACTOR if self.wheel_on_right: self.pose.yaw *= -1 self.pose.steer_yaw_offset *= -1 self.wheel_on_right_last = self.wheel_on_right - self.pose.pitch_std = driver_data.faceOrientationStd[0] - self.pose.yaw_std = driver_data.faceOrientationStd[1] - model_std_max = max(self.pose.pitch_std, self.pose.yaw_std) - self.pose.low_std = model_std_max < self.settings._POSESTD_THRESHOLD + self.model_std_max = max(driver_data.faceOrientationStd[0], driver_data.faceOrientationStd[1]) + self.pose.low_std = self.model_std_max < self.settings._HI_STD_THRESHOLD self.blink.left = driver_data.leftBlinkProb * (driver_data.leftEyeProb > self.settings._EYE_THRESHOLD) \ * (driver_data.sunglassesProb < self.settings._SG_THRESHOLD) self.blink.right = driver_data.rightBlinkProb * (driver_data.rightEyeProb > self.settings._EYE_THRESHOLD) \ * (driver_data.sunglassesProb < self.settings._SG_THRESHOLD) self.phone_prob = driver_data.phoneProb - self.distracted_types = self._get_distracted_types() - self.driver_distracted = (DistractedType.DISTRACTED_PHONE in self.distracted_types - or DistractedType.DISTRACTED_POSE in self.distracted_types - or DistractedType.DISTRACTED_BLINK in self.distracted_types) \ - and driver_data.faceProb > self.settings._FACE_THRESHOLD and self.pose.low_std + self._get_distracted_types() + self.driver_distracted = any(self.distracted_types.values()) and driver_data.faceProb > self.settings._FACE_THRESHOLD and self.pose.low_std self.driver_distraction_filter.update(self.driver_distracted) - # update offseter - # only update when driver is actively driving the car above a certain speed + # only update offsetter when driver is actively driving the car above a certain speed if self.face_detected and car_speed > self.settings._POSE_CALIB_MIN_SPEED and self.pose.low_std and (not op_engaged or not self.driver_distracted): - self.pose.pitch_offseter.push_and_update(self.pose.pitch) - self.pose.yaw_offseter.push_and_update(self.pose.yaw) + self.pose.pitch_offsetter.push_and_update(self.pose.pitch) + self.pose.yaw_offsetter.push_and_update(self.pose.yaw) - self.pose.calibrated = self.pose.pitch_offseter.filtered_stat.n > self.settings._POSE_OFFSET_MIN_COUNT and \ - self.pose.yaw_offseter.filtered_stat.n > self.settings._POSE_OFFSET_MIN_COUNT + self.pose.calibrated = self.pose.pitch_offsetter.filtered_stat.n >= self.settings._POSE_OFFSET_MIN_COUNT and \ + self.pose.yaw_offsetter.filtered_stat.n >= self.settings._POSE_OFFSET_MIN_COUNT if self.face_detected and not self.driver_distracted: - if model_std_max > self.settings._DCAM_UNCERTAIN_ALERT_THRESHOLD: - if not standstill: - self.dcam_uncertain_cnt += 1 - self.dcam_reset_cnt = 0 + dcam_uncertain = self.model_std_max > self.settings._DCAM_UNCERTAIN_ALERT_THRESHOLD + if dcam_uncertain and not standstill: + self.dcam_uncertain_cnt += 1 + self.dcam_reset_cnt = 0 else: self.dcam_reset_cnt += 1 if self.dcam_reset_cnt > self.settings._DCAM_UNCERTAIN_RESET_COUNT: self.dcam_uncertain_cnt = 0 - self.is_model_uncertain = self.hi_stds > self.settings._HI_STD_FALLBACK_TIME - self._set_timers(self.face_detected and not self.is_model_uncertain) + self.is_model_uncertain = self.hi_stds >= self.settings._HI_STD_FALLBACK_TIME + self._set_policy(MonitoringPolicy.vision if self.face_detected and not self.is_model_uncertain else MonitoringPolicy.wheeltouch) if self.face_detected and not self.pose.low_std and not self.driver_distracted: self.hi_stds += 1 elif self.face_detected and self.pose.low_std: self.hi_stds = 0 - def _update_events(self, driver_engaged, op_engaged, standstill, wrong_gear, car_speed): - self._reset_events() - # Block engaging until ignition cycle after max number or time of distractions + def _update_events(self, driver_engaged, op_engaged, standstill, wrong_gear): + self.alert_level = AlertLevel.none + self.driver_interacting = driver_engaged + if self.terminal_alert_cnt >= self.settings._MAX_TERMINAL_ALERTS or \ self.terminal_time >= self.settings._MAX_TERMINAL_DURATION: - if not self.too_distracted: - self.params.put_bool_nonblocking("DriverTooDistracted", True) self.too_distracted = True - # Always-on distraction lockout is temporary - if self.too_distracted or (self.always_on and self.awareness <= self.threshold_prompt): - self.current_events.add(EventName.tooDistracted) - always_on_valid = self.always_on and not wrong_gear - if (driver_engaged and self.awareness > 0 and not self.active_monitoring_mode) or \ + if (self.driver_interacting and self.awareness > 0 and self.active_policy == MonitoringPolicy.wheeltouch) or \ (not always_on_valid and not op_engaged) or \ (always_on_valid and not op_engaged and self.awareness <= 0): # always reset on disengage with normal mode; disengage resets only on red if always on @@ -355,111 +312,118 @@ class DriverMonitoring: return awareness_prev = self.awareness - _reaching_pre = self.awareness - self.step_change <= self.threshold_pre - _reaching_terminal = self.awareness - self.step_change <= 0 - standstill_orange_exemption = standstill and _reaching_pre - always_on_red_exemption = always_on_valid and not op_engaged and _reaching_terminal + _reaching_alert_1 = self.awareness - self.step_change <= self.threshold_alert_1 + _reaching_alert_3 = self.awareness - self.step_change <= 0 + standstill_exemption = standstill and _reaching_alert_1 + always_on_exemption = always_on_valid and not op_engaged and _reaching_alert_3 if self.awareness > 0 and \ - ((self.driver_distraction_filter.x < 0.37 and self.face_detected and self.pose.low_std) or standstill_orange_exemption): - if driver_engaged: + ((self.driver_distraction_filter.x < 0.37 and self.face_detected and self.pose.low_std) or standstill_exemption): + if self.driver_interacting: self._reset_awareness() return # only restore awareness when paying attention and alert is not red - self.awareness = min(self.awareness + ((self.settings._RECOVERY_FACTOR_MAX-self.settings._RECOVERY_FACTOR_MIN)* - (1.-self.awareness)+self.settings._RECOVERY_FACTOR_MIN)*self.step_change, 1.) + self.awareness = min(self.awareness + ((self.settings._TIMEOUT_RECOVERY_FACTOR_MAX-self.settings._TIMEOUT_RECOVERY_FACTOR_MIN)* + (1.-self.awareness)+self.settings._TIMEOUT_RECOVERY_FACTOR_MIN)*self.step_change, 1.) if self.awareness == 1.: - self.awareness_passive = min(self.awareness_passive + self.step_change, 1.) + self.last_wheeltouch_awareness = min(self.last_wheeltouch_awareness + self.step_change, 1.) # don't display alert banner when awareness is recovering and has cleared orange - if self.awareness > self.threshold_prompt: + if self.awareness > self.threshold_alert_2: return certainly_distracted = self.driver_distraction_filter.x > 0.63 and self.driver_distracted and self.face_detected - maybe_distracted = self.hi_stds > self.settings._HI_STD_FALLBACK_TIME or not self.face_detected + maybe_distracted = self.is_model_uncertain or not self.face_detected if certainly_distracted or maybe_distracted: # should always be counting if distracted unless at standstill and reaching green # also will not be reaching 0 if DM is active when not engaged - if not (standstill_orange_exemption or always_on_red_exemption): + if not (standstill_exemption or always_on_exemption): self.awareness = max(self.awareness - self.step_change, -0.1) - alert = None if self.awareness <= 0.: - # terminal red alert: disengagement required - alert = EventName.driverDistracted3 if self.active_monitoring_mode else EventName.driverUnresponsive3 + # terminal alert: disengagement required + self.alert_level = AlertLevel.three self.terminal_time += 1 if awareness_prev > 0.: self.terminal_alert_cnt += 1 - elif self.awareness <= self.threshold_prompt: - # prompt orange alert - alert = EventName.driverDistracted2 if self.active_monitoring_mode else EventName.driverUnresponsive2 - elif self.awareness <= self.threshold_pre: - # pre green alert - alert = EventName.driverDistracted1 if self.active_monitoring_mode else EventName.driverUnresponsive1 - - if alert is not None: - self.current_events.add(alert) - - if self.dcam_uncertain_cnt > self.settings._DCAM_UNCERTAIN_ALERT_COUNT and not self.dcam_uncertain_alerted: - set_offroad_alert("Offroad_DriverMonitoringUncertain", True) - self.dcam_uncertain_alerted = True - + elif self.awareness <= self.threshold_alert_2: + self.alert_level = AlertLevel.two + elif self.awareness <= self.threshold_alert_1: + self.alert_level = AlertLevel.one def get_state_packet(self, valid=True): # build driverMonitoringState packet dat = messaging.new_message('driverMonitoringState', valid=valid) - dat.driverMonitoringState = { - "events": self.current_events.to_msg(), - "faceDetected": self.face_detected, - "isDistracted": self.driver_distracted, - "distractedType": sum(self.distracted_types), - "awarenessStatus": self.awareness, - "posePitchOffset": self.pose.pitch_offseter.filtered_stat.mean(), - "posePitchValidCount": self.pose.pitch_offseter.filtered_stat.n, - "poseYawOffset": self.pose.yaw_offseter.filtered_stat.mean(), - "poseYawValidCount": self.pose.yaw_offseter.filtered_stat.n, - "stepChange": self.step_change, - "awarenessActive": self.awareness_active, - "awarenessPassive": self.awareness_passive, - "isLowStd": self.pose.low_std, - "hiStdCount": self.hi_stds, - "isActiveMode": self.active_monitoring_mode, - "isRHD": self.wheel_on_right, - "uncertainCount": self.dcam_uncertain_cnt, - } + dm = dat.driverMonitoringState + + dm.lockout = self.too_distracted + dm.alertCountLockoutPercent = to_percent(self.terminal_alert_cnt / self.settings._MAX_TERMINAL_ALERTS) + dm.alertTimeLockoutPercent = to_percent(self.terminal_time / self.settings._MAX_TERMINAL_DURATION) + dm.alwaysOn = self.always_on + dm.alwaysOnLockout = self.always_on and self.awareness <= self.threshold_alert_2 + dm.alertLevel = self.alert_level + dm.activePolicy = self.active_policy + dm.isRHD = self.wheel_on_right + dm.rhdCalibration.calibratedPercent = to_percent(self.wheelpos_offsetter.filtered_stat.n / self.settings._WHEELPOS_FILTER_MIN_COUNT) + dm.rhdCalibration.offset = self.wheelpos_offsetter.filtered_stat.M + + dm.visionPolicyState.awarenessPercent = to_percent(self.last_vision_awareness if self.active_policy != MonitoringPolicy.vision else self.awareness) + dm.visionPolicyState.awarenessStep = self.step_change if self.active_policy == MonitoringPolicy.vision else 0. + dm.visionPolicyState.isDistracted = self.driver_distracted + dm.visionPolicyState.distractedTypes.pose = self.distracted_types['pose'] + dm.visionPolicyState.distractedTypes.eye = self.distracted_types['eye'] + dm.visionPolicyState.distractedTypes.phone = self.distracted_types['phone'] + dm.visionPolicyState.faceDetected = self.face_detected + dm.visionPolicyState.pose.pitch = self.pose.pitch + dm.visionPolicyState.pose.yaw = self.pose.yaw + dm.visionPolicyState.pose.calibrated = self.pose.calibrated + dm.visionPolicyState.pose.pitchCalib.calibratedPercent = to_percent(self.pose.pitch_offsetter.filtered_stat.n / self.settings._POSE_OFFSET_MIN_COUNT) + dm.visionPolicyState.pose.pitchCalib.offset = self.pose.pitch_offsetter.filtered_stat.M + dm.visionPolicyState.pose.yawCalib.calibratedPercent = to_percent(self.pose.yaw_offsetter.filtered_stat.n / self.settings._POSE_OFFSET_MIN_COUNT) + dm.visionPolicyState.pose.yawCalib.offset = self.pose.yaw_offsetter.filtered_stat.M + dm.visionPolicyState.pose.uncertainty = self.model_std_max + dm.visionPolicyState.wheeltouchFallbackPercent = to_percent(self.hi_stds / self.settings._HI_STD_FALLBACK_TIME) + dm.visionPolicyState.uncertainOffroadAlertPercent = to_percent(self.dcam_uncertain_cnt / self.settings._DCAM_UNCERTAIN_ALERT_COUNT) + + dm.wheeltouchPolicyState.awarenessPercent = to_percent(self.last_wheeltouch_awareness if self.active_policy == MonitoringPolicy.vision else self.awareness) + dm.wheeltouchPolicyState.awarenessStep = 0. if self.active_policy == MonitoringPolicy.vision else self.step_change + dm.wheeltouchPolicyState.driverInteracting = self.driver_interacting return dat def run_step(self, sm, demo=False): if demo: - highway_speed = 30 + car_speed = 30 enabled = True wrong_gear = False standstill = False driver_engaged = False brake_disengage_prob = 1.0 + steering_angle_deg = 0.0 rpyCalib = [0., 0., 0.] else: - highway_speed = sm['carState'].vEgo + car_speed = sm['carState'].vEgo enabled = sm['selfdriveState'].enabled or sm['carControl'].latActive wrong_gear = sm['carState'].gearShifter not in (car.CarState.GearShifter.drive, car.CarState.GearShifter.low) standstill = sm['carState'].standstill driver_engaged = sm['carState'].steeringPressed or (sm['selfdriveState'].enabled and sm['carState'].gasPressed) brake_disengage_prob = sm['modelV2'].meta.disengagePredictions.brakeDisengageProbs[0] # brake disengage prob in next 2s + steering_angle_deg = sm['carState'].steeringAngleDeg rpyCalib = sm['liveCalibration'].rpyCalib - self._set_policy( + + self._set_pose_strictness( brake_disengage_prob=brake_disengage_prob, - car_speed=highway_speed, + car_speed=car_speed, ) # Parse data from dmonitoringmodeld self._update_states( driver_state=sm['driverStateV2'], cal_rpy=rpyCalib, - car_speed=highway_speed, + car_speed=car_speed, op_engaged=enabled, standstill=standstill, demo_mode=demo, - steering_angle_deg=sm['carState'].steeringAngleDeg, + steering_angle_deg=steering_angle_deg, ) # Update distraction events @@ -468,5 +432,4 @@ class DriverMonitoring: op_engaged=enabled, standstill=standstill, wrong_gear=wrong_gear, - car_speed=highway_speed ) diff --git a/selfdrive/monitoring/test_monitoring.py b/selfdrive/monitoring/test_monitoring.py index 8306889e5b..f933facdee 100644 --- a/selfdrive/monitoring/test_monitoring.py +++ b/selfdrive/monitoring/test_monitoring.py @@ -3,17 +3,16 @@ import pytest from cereal import log, car from openpilot.common.realtime import DT_DMON -from openpilot.selfdrive.monitoring.helpers import DriverMonitoring, DRIVER_MONITOR_SETTINGS -from openpilot.system.hardware import HARDWARE +from openpilot.selfdrive.monitoring.policy import DriverMonitoring, DRIVER_MONITOR_SETTINGS EventName = log.OnroadEvent.EventName -dm_settings = DRIVER_MONITOR_SETTINGS(device_type=HARDWARE.get_device_type()) +dm_settings = DRIVER_MONITOR_SETTINGS() TEST_TIMESPAN = 120 # seconds -DISTRACTED_SECONDS_TO_ORANGE = dm_settings._DISTRACTED_TIME - dm_settings._DISTRACTED_PROMPT_TIME_TILL_TERMINAL + 1 -DISTRACTED_SECONDS_TO_RED = dm_settings._DISTRACTED_TIME + 1 -INVISIBLE_SECONDS_TO_ORANGE = dm_settings._AWARENESS_TIME - dm_settings._AWARENESS_PROMPT_TIME_TILL_TERMINAL + 1 -INVISIBLE_SECONDS_TO_RED = dm_settings._AWARENESS_TIME + 1 +DISTRACTED_SECONDS_TO_ORANGE = dm_settings._VISION_POLICY_ALERT_2_TIMEOUT + 1 +DISTRACTED_SECONDS_TO_RED = dm_settings._VISION_POLICY_ALERT_3_TIMEOUT + 1 +INVISIBLE_SECONDS_TO_ORANGE = dm_settings._WHEELTOUCH_POLICY_ALERT_2_TIMEOUT + 1 +INVISIBLE_SECONDS_TO_RED = dm_settings._WHEELTOUCH_POLICY_ALERT_3_TIMEOUT + 1 def make_msg(face_detected, distracted=False, model_uncertain=False): ds = log.DriverStateV2.new_message() @@ -37,7 +36,7 @@ msg_ATTENTIVE = make_msg(True) msg_DISTRACTED = make_msg(True, distracted=True) msg_ATTENTIVE_UNCERTAIN = make_msg(True, model_uncertain=True) msg_DISTRACTED_UNCERTAIN = make_msg(True, distracted=True, model_uncertain=True) -msg_DISTRACTED_BUT_SOMEHOW_UNCERTAIN = make_msg(True, distracted=True, model_uncertain=dm_settings._POSESTD_THRESHOLD*1.5) +msg_DISTRACTED_BUT_SOMEHOW_UNCERTAIN = make_msg(True, distracted=True, model_uncertain=dm_settings._HI_STD_THRESHOLD*1.5) # driver interaction with car car_interaction_DETECTED = True @@ -53,49 +52,49 @@ always_false = [False] * int(TEST_TIMESPAN / DT_DMON) class TestMonitoring: def _run_seq(self, msgs, interaction, engaged, standstill): DM = DriverMonitoring() - events = [] + alert_lvls = [] for idx in range(len(msgs)): DM._update_states(msgs[idx], [0, 0, 0], 0, engaged[idx], standstill[idx]) # cal_rpy and car_speed don't matter here # evaluate events at 10Hz for tests - DM._update_events(interaction[idx], engaged[idx], standstill[idx], 0, 0) - events.append(DM.current_events) - assert len(events) == len(msgs), f"got {len(events)} for {len(msgs)} driverState input msgs" - return events, DM + DM._update_events(interaction[idx], engaged[idx], standstill[idx], 0) + alert_lvls.append(DM.alert_level) + assert len(alert_lvls) == len(msgs), f"got {len(alert_lvls)} for {len(msgs)} driverState input msgs" + return alert_lvls, DM - def _assert_no_events(self, events): - assert all(not len(e) for e in events) # engaged, driver is attentive all the time def test_fully_aware_driver(self): - events, _ = self._run_seq(always_attentive, always_false, always_true, always_false) - self._assert_no_events(events) + alert_lvls, d_status = self._run_seq(always_attentive, always_false, always_true, always_false) + assert all(a == 0 for a in alert_lvls) + assert d_status.active_policy == log.DriverMonitoringState.MonitoringPolicy.vision # engaged, driver is distracted and does nothing def test_fully_distracted_driver(self): - events, d_status = self._run_seq(always_distracted, always_false, always_true, always_false) - assert len(events[int((d_status.settings._DISTRACTED_TIME-d_status.settings._DISTRACTED_PRE_TIME_TILL_TERMINAL)/2/DT_DMON)]) == 0 - assert events[int((d_status.settings._DISTRACTED_TIME-d_status.settings._DISTRACTED_PRE_TIME_TILL_TERMINAL + \ - ((d_status.settings._DISTRACTED_PRE_TIME_TILL_TERMINAL-d_status.settings._DISTRACTED_PROMPT_TIME_TILL_TERMINAL)/2))/DT_DMON)].names[0] == \ - EventName.driverDistracted1 - assert events[int((d_status.settings._DISTRACTED_TIME-d_status.settings._DISTRACTED_PROMPT_TIME_TILL_TERMINAL + \ - ((d_status.settings._DISTRACTED_PROMPT_TIME_TILL_TERMINAL)/2))/DT_DMON)].names[0] == EventName.driverDistracted2 - assert events[int((d_status.settings._DISTRACTED_TIME + \ - ((TEST_TIMESPAN-10-d_status.settings._DISTRACTED_TIME)/2))/DT_DMON)].names[0] == EventName.driverDistracted3 + alert_lvls, d_status = self._run_seq(always_distracted, always_false, always_true, always_false) + s = d_status.settings + assert alert_lvls[int(s._VISION_POLICY_ALERT_1_TIMEOUT / 2 / DT_DMON)] == 0 + assert alert_lvls[int((s._VISION_POLICY_ALERT_1_TIMEOUT + \ + (s._VISION_POLICY_ALERT_2_TIMEOUT - s._VISION_POLICY_ALERT_1_TIMEOUT) / 2) / DT_DMON)] == 1 + assert alert_lvls[int((s._VISION_POLICY_ALERT_2_TIMEOUT + \ + (s._VISION_POLICY_ALERT_3_TIMEOUT - s._VISION_POLICY_ALERT_2_TIMEOUT) / 2) / DT_DMON)] == 2 + assert alert_lvls[int((s._VISION_POLICY_ALERT_3_TIMEOUT + \ + (TEST_TIMESPAN - 10 - s._VISION_POLICY_ALERT_3_TIMEOUT) / 2) / DT_DMON)] == 3 assert isinstance(d_status.awareness, float) # engaged, no face detected the whole time, no action def test_fully_invisible_driver(self): - events, d_status = self._run_seq(always_no_face, always_false, always_true, always_false) - assert len(events[int((d_status.settings._AWARENESS_TIME-d_status.settings._AWARENESS_PRE_TIME_TILL_TERMINAL)/2/DT_DMON)]) == 0 - assert events[int((d_status.settings._AWARENESS_TIME-d_status.settings._AWARENESS_PRE_TIME_TILL_TERMINAL + \ - ((d_status.settings._AWARENESS_PRE_TIME_TILL_TERMINAL-d_status.settings._AWARENESS_PROMPT_TIME_TILL_TERMINAL)/2))/DT_DMON)].names[0] == \ - EventName.driverUnresponsive1 - assert events[int((d_status.settings._AWARENESS_TIME-d_status.settings._AWARENESS_PROMPT_TIME_TILL_TERMINAL + \ - ((d_status.settings._AWARENESS_PROMPT_TIME_TILL_TERMINAL)/2))/DT_DMON)].names[0] == EventName.driverUnresponsive2 - assert events[int((d_status.settings._AWARENESS_TIME + \ - ((TEST_TIMESPAN-10-d_status.settings._AWARENESS_TIME)/2))/DT_DMON)].names[0] == EventName.driverUnresponsive3 + alert_lvls, d_status = self._run_seq(always_no_face, always_false, always_true, always_false) + s = d_status.settings + assert alert_lvls[int(s._WHEELTOUCH_POLICY_ALERT_1_TIMEOUT / 2 / DT_DMON)] == 0 + assert alert_lvls[int((s._WHEELTOUCH_POLICY_ALERT_1_TIMEOUT + \ + (s._WHEELTOUCH_POLICY_ALERT_2_TIMEOUT - s._WHEELTOUCH_POLICY_ALERT_1_TIMEOUT) / 2) / DT_DMON)] == 1 + assert alert_lvls[int((s._WHEELTOUCH_POLICY_ALERT_2_TIMEOUT + \ + (s._WHEELTOUCH_POLICY_ALERT_3_TIMEOUT - s._WHEELTOUCH_POLICY_ALERT_2_TIMEOUT) / 2) / DT_DMON)] == 2 + assert alert_lvls[int((s._WHEELTOUCH_POLICY_ALERT_3_TIMEOUT + \ + (TEST_TIMESPAN - 10 - s._WHEELTOUCH_POLICY_ALERT_3_TIMEOUT) / 2) / DT_DMON)] == 3 + assert d_status.active_policy == log.DriverMonitoringState.MonitoringPolicy.wheeltouch # engaged, down to orange, driver pays attention, back to normal; then down to orange, driver touches wheel # - should have short orange recovery time and no green afterwards; wheel touch only recovers when paying attention @@ -106,13 +105,13 @@ class TestMonitoring: [msg_ATTENTIVE] * (int(TEST_TIMESPAN/DT_DMON)-int((DISTRACTED_SECONDS_TO_ORANGE*3+2)/DT_DMON)) interaction_vector = [car_interaction_NOT_DETECTED] * int(DISTRACTED_SECONDS_TO_ORANGE*3/DT_DMON) + \ [car_interaction_DETECTED] * (int(TEST_TIMESPAN/DT_DMON)-int(DISTRACTED_SECONDS_TO_ORANGE*3/DT_DMON)) - events, _ = self._run_seq(ds_vector, interaction_vector, always_true, always_false) - assert len(events[int(DISTRACTED_SECONDS_TO_ORANGE*0.5/DT_DMON)]) == 0 - assert events[int((DISTRACTED_SECONDS_TO_ORANGE-0.1)/DT_DMON)].names[0] == EventName.driverDistracted2 - assert len(events[int(DISTRACTED_SECONDS_TO_ORANGE*1.5/DT_DMON)]) == 0 - assert events[int((DISTRACTED_SECONDS_TO_ORANGE*3-0.1)/DT_DMON)].names[0] == EventName.driverDistracted2 - assert events[int((DISTRACTED_SECONDS_TO_ORANGE*3+0.1)/DT_DMON)].names[0] == EventName.driverDistracted2 - assert len(events[int((DISTRACTED_SECONDS_TO_ORANGE*3+2.5)/DT_DMON)]) == 0 + alert_lvls, _ = self._run_seq(ds_vector, interaction_vector, always_true, always_false) + assert alert_lvls[int(DISTRACTED_SECONDS_TO_ORANGE*0.5/DT_DMON)] == 0 + assert alert_lvls[int((DISTRACTED_SECONDS_TO_ORANGE-0.1)/DT_DMON)] == 2 + assert alert_lvls[int(DISTRACTED_SECONDS_TO_ORANGE*1.5/DT_DMON)] == 0 + assert alert_lvls[int((DISTRACTED_SECONDS_TO_ORANGE*3-0.1)/DT_DMON)] == 2 + assert alert_lvls[int((DISTRACTED_SECONDS_TO_ORANGE*3+0.1)/DT_DMON)] == 2 + assert alert_lvls[int((DISTRACTED_SECONDS_TO_ORANGE*3+2.5)/DT_DMON)] == 0 # engaged, down to orange, driver dodges camera, then comes back still distracted, down to red, \ # driver dodges, and then touches wheel to no avail, disengages and reengages @@ -130,11 +129,11 @@ class TestMonitoring: = [True] * int(1/DT_DMON) op_vector[int((DISTRACTED_SECONDS_TO_RED+2*_invisible_time+2.5)/DT_DMON):int((DISTRACTED_SECONDS_TO_RED+2*_invisible_time+3)/DT_DMON)] \ = [False] * int(0.5/DT_DMON) - events, _ = self._run_seq(ds_vector, interaction_vector, op_vector, always_false) - assert events[int((DISTRACTED_SECONDS_TO_ORANGE+0.5*_invisible_time)/DT_DMON)].names[0] == EventName.driverDistracted2 - assert events[int((DISTRACTED_SECONDS_TO_RED+1.5*_invisible_time)/DT_DMON)].names[0] == EventName.driverDistracted3 - assert events[int((DISTRACTED_SECONDS_TO_RED+2*_invisible_time+1.5)/DT_DMON)].names[0] == EventName.driverDistracted3 - assert len(events[int((DISTRACTED_SECONDS_TO_RED+2*_invisible_time+3.5)/DT_DMON)]) == 0 + alert_lvls, _ = self._run_seq(ds_vector, interaction_vector, op_vector, always_false) + assert alert_lvls[int((DISTRACTED_SECONDS_TO_ORANGE+0.5*_invisible_time)/DT_DMON)] == 2 + assert alert_lvls[int((DISTRACTED_SECONDS_TO_RED+1.5*_invisible_time)/DT_DMON)] == 3 + assert alert_lvls[int((DISTRACTED_SECONDS_TO_RED+2*_invisible_time+1.5)/DT_DMON)] == 3 + assert alert_lvls[int((DISTRACTED_SECONDS_TO_RED+2*_invisible_time+3.5)/DT_DMON)] == 0 # engaged, invisible driver, down to orange, driver touches wheel; then down to orange again, driver appears # - both actions should clear the alert, but momentary appearance should not @@ -145,16 +144,16 @@ class TestMonitoring: ds_vector[int((2*INVISIBLE_SECONDS_TO_ORANGE+1)/DT_DMON):int((2*INVISIBLE_SECONDS_TO_ORANGE+1+_visible_time)/DT_DMON)] = \ [msg_ATTENTIVE] * int(_visible_time/DT_DMON) interaction_vector[int((INVISIBLE_SECONDS_TO_ORANGE)/DT_DMON):int((INVISIBLE_SECONDS_TO_ORANGE+1)/DT_DMON)] = [True] * int(1/DT_DMON) - events, _ = self._run_seq(ds_vector, interaction_vector, 2*always_true, 2*always_false) - assert len(events[int(INVISIBLE_SECONDS_TO_ORANGE*0.5/DT_DMON)]) == 0 - assert events[int((INVISIBLE_SECONDS_TO_ORANGE-0.1)/DT_DMON)].names[0] == EventName.driverUnresponsive2 - assert len(events[int((INVISIBLE_SECONDS_TO_ORANGE+0.1)/DT_DMON)]) == 0 + alert_lvls, _ = self._run_seq(ds_vector, interaction_vector, 2*always_true, 2*always_false) + assert alert_lvls[int(INVISIBLE_SECONDS_TO_ORANGE*0.5/DT_DMON)] == 0 + assert alert_lvls[int((INVISIBLE_SECONDS_TO_ORANGE-0.1)/DT_DMON)] == 2 + assert alert_lvls[int((INVISIBLE_SECONDS_TO_ORANGE+0.1)/DT_DMON)] == 0 if _visible_time == 0.5: - assert events[int((INVISIBLE_SECONDS_TO_ORANGE*2+1-0.1)/DT_DMON)].names[0] == EventName.driverUnresponsive2 - assert events[int((INVISIBLE_SECONDS_TO_ORANGE*2+1+0.1+_visible_time)/DT_DMON)].names[0] == EventName.driverUnresponsive1 + assert alert_lvls[int((INVISIBLE_SECONDS_TO_ORANGE*2+1-0.1)/DT_DMON)] == 2 + assert alert_lvls[int((INVISIBLE_SECONDS_TO_ORANGE*2+1+0.1+_visible_time)/DT_DMON)] == 1 elif _visible_time == 10: - assert events[int((INVISIBLE_SECONDS_TO_ORANGE*2+1-0.1)/DT_DMON)].names[0] == EventName.driverUnresponsive2 - assert len(events[int((INVISIBLE_SECONDS_TO_ORANGE*2+1+0.1+_visible_time)/DT_DMON)]) == 0 + assert alert_lvls[int((INVISIBLE_SECONDS_TO_ORANGE*2+1-0.1)/DT_DMON)] == 2 + assert alert_lvls[int((INVISIBLE_SECONDS_TO_ORANGE*2+1+0.1+_visible_time)/DT_DMON)] == 0 # engaged, invisible driver, down to red, driver appears and then touches wheel, then disengages/reengages # - only disengage will clear the alert @@ -166,19 +165,19 @@ class TestMonitoring: ds_vector[int(INVISIBLE_SECONDS_TO_RED/DT_DMON):int((INVISIBLE_SECONDS_TO_RED+_visible_time)/DT_DMON)] = [msg_ATTENTIVE] * int(_visible_time/DT_DMON) interaction_vector[int((INVISIBLE_SECONDS_TO_RED+_visible_time)/DT_DMON):int((INVISIBLE_SECONDS_TO_RED+_visible_time+1)/DT_DMON)] = [True] * int(1/DT_DMON) op_vector[int((INVISIBLE_SECONDS_TO_RED+_visible_time+1)/DT_DMON):int((INVISIBLE_SECONDS_TO_RED+_visible_time+0.5)/DT_DMON)] = [False] * int(0.5/DT_DMON) - events, _ = self._run_seq(ds_vector, interaction_vector, op_vector, always_false) - assert len(events[int(INVISIBLE_SECONDS_TO_ORANGE*0.5/DT_DMON)]) == 0 - assert events[int((INVISIBLE_SECONDS_TO_ORANGE-0.1)/DT_DMON)].names[0] == EventName.driverUnresponsive2 - assert events[int((INVISIBLE_SECONDS_TO_RED-0.1)/DT_DMON)].names[0] == EventName.driverUnresponsive3 - assert events[int((INVISIBLE_SECONDS_TO_RED+0.5*_visible_time)/DT_DMON)].names[0] == EventName.driverUnresponsive3 - assert events[int((INVISIBLE_SECONDS_TO_RED+_visible_time+0.5)/DT_DMON)].names[0] == EventName.driverUnresponsive3 - assert len(events[int((INVISIBLE_SECONDS_TO_RED+_visible_time+1+0.1)/DT_DMON)]) == 0 + alert_lvls, _ = self._run_seq(ds_vector, interaction_vector, op_vector, always_false) + assert alert_lvls[int(INVISIBLE_SECONDS_TO_ORANGE*0.5/DT_DMON)] == 0 + assert alert_lvls[int((INVISIBLE_SECONDS_TO_ORANGE-0.1)/DT_DMON)] == 2 + assert alert_lvls[int((INVISIBLE_SECONDS_TO_RED-0.1)/DT_DMON)] == 3 + assert alert_lvls[int((INVISIBLE_SECONDS_TO_RED+0.5*_visible_time)/DT_DMON)] == 3 + assert alert_lvls[int((INVISIBLE_SECONDS_TO_RED+_visible_time+0.5)/DT_DMON)] == 3 + assert alert_lvls[int((INVISIBLE_SECONDS_TO_RED+_visible_time+1+0.1)/DT_DMON)] == 0 # disengaged, always distracted driver # - dm should stay quiet when not engaged def test_pure_dashcam_user(self): - events, _ = self._run_seq(always_distracted, always_false, always_false, always_false) - assert sum(len(event) for event in events) == 0 + alert_lvls, _ = self._run_seq(always_distracted, always_false, always_false, always_false) + assert all(a == 0 for a in alert_lvls) # engaged, car stops at traffic light, down to orange, no action, then car starts moving # - should only reach green when stopped, but continues counting down on launch @@ -186,11 +185,12 @@ class TestMonitoring: _redlight_time = 60 # seconds standstill_vector = always_true[:] standstill_vector[int(_redlight_time/DT_DMON):] = [False] * int((TEST_TIMESPAN-_redlight_time)/DT_DMON) - events, d_status = self._run_seq(always_distracted, always_false, always_true, standstill_vector) - assert len(events[int((_redlight_time-0.1)/DT_DMON)]) == 0 - _pre_to_prompt = d_status.settings._DISTRACTED_PRE_TIME_TILL_TERMINAL - d_status.settings._DISTRACTED_PROMPT_TIME_TILL_TERMINAL - assert events[int((_redlight_time+0.5)/DT_DMON)].names[0] == EventName.driverDistracted1 - assert events[int((_redlight_time+_pre_to_prompt+0.5)/DT_DMON)].names[0] == EventName.driverDistracted2 + alert_lvls, d_status = self._run_seq(always_distracted, always_false, always_true, standstill_vector) + s = d_status.settings + assert alert_lvls[int((_redlight_time-0.1)/DT_DMON)] == 0 + _alert_1_to_2 = s._VISION_POLICY_ALERT_2_TIMEOUT - s._VISION_POLICY_ALERT_1_TIMEOUT + assert alert_lvls[int((_redlight_time+0.5)/DT_DMON)] == 1 + assert alert_lvls[int((_redlight_time+_alert_1_to_2+0.5)/DT_DMON)] == 2 # engaged, distracted while moving, then car stops after reaching orange # - should reset timer to pre green at standstill @@ -198,23 +198,21 @@ class TestMonitoring: _stop_time = DISTRACTED_SECONDS_TO_ORANGE + 1 # stop 1 second after reaching orange standstill_vector = always_false[:] standstill_vector[int(_stop_time/DT_DMON):] = [True] * int((TEST_TIMESPAN-_stop_time)/DT_DMON) - events, _ = self._run_seq(always_distracted, always_false, always_true, standstill_vector) + alert_lvls, _ = self._run_seq(always_distracted, always_false, always_true, standstill_vector) # just before and briefly after stopping: orange alert; goes away quickly after stopped - assert events[int((_stop_time+0.1)/DT_DMON)].names[0] == EventName.driverDistracted2 - assert len(events[int((_stop_time+0.5)/DT_DMON)]) == 0 + assert alert_lvls[int((_stop_time+0.1)/DT_DMON)] == 2 + assert alert_lvls[int((_stop_time+0.5)/DT_DMON)] == 0 # engaged, model is somehow uncertain and driver is distracted # - should fall back to wheel touch after uncertain alert def test_somehow_indecisive_model(self): ds_vector = [msg_DISTRACTED_BUT_SOMEHOW_UNCERTAIN] * int(TEST_TIMESPAN/DT_DMON) interaction_vector = always_false[:] - events, d_status = self._run_seq(ds_vector, interaction_vector, always_true, always_false) - assert EventName.driverUnresponsive1 in \ - events[int((INVISIBLE_SECONDS_TO_ORANGE-1+DT_DMON*d_status.settings._HI_STD_FALLBACK_TIME-0.1)/DT_DMON)].names - assert EventName.driverUnresponsive2 in \ - events[int((INVISIBLE_SECONDS_TO_ORANGE-1+DT_DMON*d_status.settings._HI_STD_FALLBACK_TIME+0.1)/DT_DMON)].names - assert EventName.driverUnresponsive3 in \ - events[int((INVISIBLE_SECONDS_TO_RED-1+DT_DMON*d_status.settings._HI_STD_FALLBACK_TIME+0.1)/DT_DMON)].names + alert_lvls, d_status = self._run_seq(ds_vector, interaction_vector, always_true, always_false) + s = d_status.settings + assert alert_lvls[int((INVISIBLE_SECONDS_TO_ORANGE-1+DT_DMON*s._HI_STD_FALLBACK_TIME-0.1)/DT_DMON)] == 1 + assert alert_lvls[int((INVISIBLE_SECONDS_TO_ORANGE-1+DT_DMON*s._HI_STD_FALLBACK_TIME+0.1)/DT_DMON)] == 2 + assert alert_lvls[int((INVISIBLE_SECONDS_TO_RED-1+DT_DMON*s._HI_STD_FALLBACK_TIME+0.1)/DT_DMON)] == 3 def _build_sm(selfdrive_enabled, lat_active, steering_pressed, gas_pressed): @@ -253,10 +251,10 @@ def test_run_step_engagement(selfdrive_enabled, lat_active, steering, gas, captured = {} orig = dm._update_events - def spy(driver_engaged, op_engaged, standstill, wrong_gear, car_speed): + def spy(driver_engaged, op_engaged, standstill, wrong_gear): captured['driver_engaged'] = driver_engaged captured['op_engaged'] = op_engaged - return orig(driver_engaged, op_engaged, standstill, wrong_gear, car_speed) + return orig(driver_engaged, op_engaged, standstill, wrong_gear) dm._update_events = spy dm.run_step(sm, demo=False) diff --git a/selfdrive/pandad/pandad.cc b/selfdrive/pandad/pandad.cc index cb60917008..a771326f9d 100644 --- a/selfdrive/pandad/pandad.cc +++ b/selfdrive/pandad/pandad.cc @@ -1,6 +1,7 @@ #include "selfdrive/pandad/pandad.h" #include +#include #include #include #include @@ -23,6 +24,14 @@ ExitHandler do_exit; +struct HwmonState { + std::atomic voltage{0}; + std::atomic current{0}; + std::atomic initialized{false}; +}; + +HwmonState hwmon_state; + bool check_connected(Panda *panda) { if (!panda->connected()) { do_exit = true; @@ -117,6 +126,26 @@ void can_recv(Panda *panda, PubMaster *pm) { } } +void hwmon_thread() { + util::set_thread_name("pandad_hwmon"); + + while (!do_exit) { + double read_time = millis_since_boot(); + uint32_t voltage = Hardware::get_voltage(); + uint32_t current = Hardware::get_current(); + read_time = millis_since_boot() - read_time; + if (read_time > 50) { + LOGW("reading hwmon took %lfms", read_time); + } + + hwmon_state.voltage.store(voltage); + hwmon_state.current.store(current); + hwmon_state.initialized.store(true); + + util::sleep_for(500); + } +} + void fill_panda_state(cereal::PandaState::Builder &ps, cereal::PandaState::PandaType hw_type, const health_t &health) { ps.setVoltage(health.voltage_pkt); ps.setCurrent(health.current_pkt); @@ -249,6 +278,10 @@ std::optional send_panda_states(PubMaster *pm, Panda *panda, bool is_onroa } void send_peripheral_state(Panda *panda, PubMaster *pm) { + if (!hwmon_state.initialized.load()) { + return; + } + // build msg MessageBuilder msg; auto evt = msg.initEvent(); @@ -257,13 +290,8 @@ void send_peripheral_state(Panda *panda, PubMaster *pm) { auto ps = evt.initPeripheralState(); ps.setPandaType(panda->hw_type); - double read_time = millis_since_boot(); - ps.setVoltage(Hardware::get_voltage()); - ps.setCurrent(Hardware::get_current()); - read_time = millis_since_boot() - read_time; - if (read_time > 50) { - LOGW("reading hwmon took %lfms", read_time); - } + ps.setVoltage(hwmon_state.voltage.load()); + ps.setCurrent(hwmon_state.current.load()); // fall back to panda's voltage and current measurement if (ps.getVoltage() == 0 && ps.getCurrent() == 0) { @@ -385,12 +413,12 @@ void pandad_run(Panda *panda) { const bool spoofing_started = getenv("STARTED") != nullptr; const bool fake_send = getenv("FAKESEND") != nullptr; - // Start the CAN send thread + // Start helper threads for event-driven sendcan and slow non-Panda reads. std::thread send_thread(can_send_thread, panda, fake_send); + std::thread hardware_thread(hwmon_thread); - Params params; RateKeeper rk("pandad", 100); - SubMaster sm({"selfdriveState", "selfdriveStateSP"}); + SubMaster sm({"selfdriveState", "deviceState", "selfdriveStateSP"}); PubMaster pm({"can", "pandaStates", "peripheralState"}); PandaSafety panda_safety(panda); bool engaged = false; @@ -398,7 +426,7 @@ void pandad_run(Panda *panda) { bool is_onroad = false; bool always_offroad = false; - // Main loop: receive CAN data and process states + // Main loop: receive CAN first, then process lower priority panda and peripheral state. while (!do_exit && check_connected(panda)) { can_recv(panda, &pm); @@ -411,8 +439,10 @@ void pandad_run(Panda *panda) { if (rk.frame() % 10 == 0) { sm.update(0); engaged = sm.allAliveAndValid({"selfdriveState"}) && sm["selfdriveState"].getSelfdriveState().getEnabled(); + if (sm.updated("deviceState")) { + is_onroad = sm["deviceState"].getDeviceState().getStarted(); + } engaged_mads = process_mads_heartbeat(&sm); - is_onroad = params.getBool("IsOnroad"); always_offroad = panda_safety.getOffroadMode(); process_panda_state(panda, &pm, engaged, engaged_mads, is_onroad, spoofing_started, always_offroad); panda_safety.configureSafetyMode(is_onroad); @@ -445,6 +475,7 @@ void pandad_run(Panda *panda) { } send_thread.join(); + hardware_thread.join(); } void pandad_main_thread(std::string serial) { diff --git a/selfdrive/pandad/pandad.py b/selfdrive/pandad/pandad.py index f65c64259f..6846abcadd 100755 --- a/selfdrive/pandad/pandad.py +++ b/selfdrive/pandad/pandad.py @@ -16,25 +16,17 @@ from openpilot.sunnypilot.selfdrive.pandad.rivian_long_flasher import flash_rivi def get_expected_signature() -> bytes: - try: - fn = os.path.join(FW_PATH, McuType.H7.config.app_fn) - return Panda.get_signature_from_firmware(fn) - except Exception: - cloudlog.exception("Error computing expected signature") - return b"" + fn = os.path.join(FW_PATH, McuType.H7.config.app_fn) + return Panda.get_signature_from_firmware(fn) -def flash_panda(panda_serial: str) -> Panda: - try: - panda = Panda(panda_serial) - except PandaProtocolMismatch: - cloudlog.warning("detected protocol mismatch, reflashing panda") - HARDWARE.recover_internal_panda() - raise +def flash_panda(panda_serial: str): + panda = Panda(panda_serial) # skip flashing if the detected panda is not supported if panda.get_type() not in Panda.SUPPORTED_DEVICES: cloudlog.warning(f"Panda {panda_serial} is not supported (hw_type: {panda.get_type()}), skipping flash...") - return panda + panda.close() + return fw_signature = get_expected_signature() internal_panda = panda.is_internal() @@ -65,7 +57,7 @@ def flash_panda(panda_serial: str) -> Panda: cloudlog.info("Version mismatch after flashing, exiting") raise AssertionError - return panda + panda.close() def check_panda_support(panda_serials: list[str]) -> list[str]: @@ -97,97 +89,56 @@ def main() -> None: do_exit = False signal.signal(signal.SIGINT, signal_handler) - count = 0 - first_run = True - params = Params() - no_internal_panda_count = 0 + # check health for lost heartbeat + try: + for s in Panda.list(): + with Panda(s) as p: + health = p.health() + if p.is_internal() and health["heartbeat_lost"]: + Params().put_bool("PandaHeartbeatLost", True, block=True) + cloudlog.event("heartbeat lost", deviceState=health) + except Exception: + cloudlog.exception("pandad.uncaught_exception") + count = 0 while not do_exit: try: - count += 1 cloudlog.event("pandad.flash_and_connect", count=count) - params.remove("PandaSignatures") - - # Handle missing internal panda - if no_internal_panda_count > 0: - if no_internal_panda_count == 3: - cloudlog.info("No pandas found, putting internal panda into DFU") - HARDWARE.recover_internal_panda() - else: - cloudlog.info("No pandas found, resetting internal panda") - HARDWARE.reset_internal_panda() - time.sleep(3) # wait to come back up + if (count % 2) == 0: + HARDWARE.reset_internal_panda() + else: + HARDWARE.recover_internal_panda() + count += 1 # Flash all Pandas in DFU mode - dfu_serials = PandaDFU.list() - if len(dfu_serials) > 0: - for serial in dfu_serials: - cloudlog.info(f"Panda in DFU mode found, flashing recovery {serial}") - PandaDFU(serial).recover() + for serial in PandaDFU.list(): + cloudlog.info(f"Panda in DFU mode found, flashing recovery {serial}") + PandaDFU(serial).recover() time.sleep(1) panda_serials = Panda.list() - if len(panda_serials) == 0: - no_internal_panda_count += 1 - continue + if len(panda_serials): + # custom flasher for xnor's Rivian Longitudinal Upgrade Kit + flash_rivian_long(panda_serials) + # find the internal supported panda (e.g. skip external Black Panda) + panda_serials = check_panda_support(panda_serials) - cloudlog.info(f"{len(panda_serials)} panda(s) found, connecting - {panda_serials}") + assert len(panda_serials) == 1 + cloudlog.info(f"{len(panda_serials)} panda found, connecting - {panda_serials}") + flash_panda(panda_serials[0]) - # custom flasher for xnor's Rivian Longitudinal Upgrade Kit - flash_rivian_long(panda_serials) - - # find the internal supported panda (e.g. skip external Black Panda) - panda_serials = check_panda_support(panda_serials) - if len(panda_serials) == 0: - continue - - # Flash the first panda - panda_serial = panda_serials[0] - panda = flash_panda(panda_serial) - - # Ensure internal panda is present if expected - if HARDWARE.has_internal_panda() and not panda.is_internal(): - cloudlog.error("Internal panda is missing, trying again") - no_internal_panda_count += 1 - continue - no_internal_panda_count = 0 - - # log panda fw version - params.put("PandaSignatures", panda.get_signature()) - - # check health for lost heartbeat - health = panda.health() - if health["heartbeat_lost"]: - params.put_bool("PandaHeartbeatLost", True) - cloudlog.event("heartbeat lost", deviceState=health, serial=panda.get_usb_serial()) - if health["som_reset_triggered"]: - params.put_bool("PandaSomResetTriggered", True) - cloudlog.event("panda.som_reset_triggered", health=health, serial=panda.get_usb_serial()) - - if first_run: - # reset panda to ensure we're in a good state - cloudlog.info(f"Resetting panda {panda.get_usb_serial()}") - panda.reset(reconnect=True) - - panda.close() + # run real pandad + os.environ['MANAGER_DAEMON'] = 'pandad' + process = subprocess.Popen(["./pandad"], cwd=os.path.join(BASEDIR, "selfdrive/pandad")) + process.wait() # TODO: wrap all panda exceptions in a base panda exception except (usb1.USBErrorNoDevice, usb1.USBErrorPipe): # a panda was disconnected while setting everything up. let's try again cloudlog.exception("Panda USB exception while setting up") - continue except PandaProtocolMismatch: cloudlog.exception("pandad.protocol_mismatch") - continue except Exception: cloudlog.exception("pandad.uncaught_exception") - continue - - first_run = False - - # run pandad with all connected serials as arguments - os.environ['MANAGER_DAEMON'] = 'pandad' - process = subprocess.Popen(["./pandad", panda_serial], cwd=os.path.join(BASEDIR, "selfdrive/pandad")) - process.wait() if __name__ == "__main__": diff --git a/selfdrive/pandad/tests/bootstub.panda_h7_spiv0.bin b/selfdrive/pandad/tests/bootstub.panda_h7_spiv0.bin deleted file mode 100755 index 5cf2fa4519..0000000000 Binary files a/selfdrive/pandad/tests/bootstub.panda_h7_spiv0.bin and /dev/null differ diff --git a/selfdrive/pandad/tests/test_pandad.py b/selfdrive/pandad/tests/test_pandad.py index 6a5840d487..9dacd3f5a8 100644 --- a/selfdrive/pandad/tests/test_pandad.py +++ b/selfdrive/pandad/tests/test_pandad.py @@ -15,12 +15,6 @@ HERE = os.path.dirname(os.path.realpath(__file__)) @pytest.mark.tici class TestPandad: - - def setup_method(self): - # ensure panda is up - if len(Panda.list()) == 0: - self._run_test(60) - def teardown_method(self): managed_processes['pandad'].stop() @@ -30,7 +24,7 @@ class TestPandad: managed_processes['pandad'].start() while (time.monotonic() - st) < timeout: - sm.update(100) + sm.update(10) if len(sm['pandaStates']) and sm['pandaStates'][0].pandaType != log.PandaState.PandaType.unknown: break dt = time.monotonic() - st @@ -45,10 +39,6 @@ class TestPandad: HARDWARE.recover_internal_panda() assert Panda.wait_for_dfu(None, 10) - def _assert_no_panda(self): - assert not Panda.wait_for_dfu(None, 3) - assert not Panda.wait_for_panda(None, 3) - def _flash_bootstub(self, fn): self._go_to_dfu() pd = PandaDFU(None) @@ -56,12 +46,11 @@ class TestPandad: fn = os.path.join(HERE, pd.get_mcu_type().config.bootstub_fn) with open(fn, "rb") as f: pd.program_bootstub(f.read()) - pd.reset() HARDWARE.reset_internal_panda() def test_in_dfu(self): HARDWARE.recover_internal_panda() - self._run_test(60) + self._run_test() def test_in_bootstub(self): with Panda() as p: @@ -69,30 +58,24 @@ class TestPandad: assert p.bootstub self._run_test() - def test_internal_panda_reset(self): + def test_in_reset(self): gpio_init(GPIO.STM_RST_N, True) gpio_set(GPIO.STM_RST_N, 1) - time.sleep(0.5) - assert all(not Panda(s).is_internal() for s in Panda.list()) + assert not Panda.list() self._run_test() - assert any(Panda(s).is_internal() for s in Panda.list()) - - def test_old_spi_protocol(self): - # flash firmware with old SPI protocol - self._flash_bootstub(os.path.join(HERE, "bootstub.panda_h7_spiv0.bin")) - self._run_test(45) - def test_release_to_devel_bootstub(self): + st = time.monotonic() self._flash_bootstub(None) - self._run_test(45) + print("flash done", time.monotonic() - st) + self._run_test() def test_recover_from_bad_bootstub(self): self._go_to_dfu() with PandaDFU(None) as pd: - pd.program_bootstub(b"\x00"*1024) - pd.reset() + pd._handle.program(pd.get_mcu_type().config.bootstub_address, b"\x00"*100) HARDWARE.reset_internal_panda() - self._assert_no_panda() + assert not Panda.list() + assert not PandaDFU.list() - self._run_test(60) + self._run_test() diff --git a/selfdrive/pandad/tests/test_pandad_loopback.py b/selfdrive/pandad/tests/test_pandad_loopback.py index fd4a99be62..bc90f42a83 100644 --- a/selfdrive/pandad/tests/test_pandad_loopback.py +++ b/selfdrive/pandad/tests/test_pandad_loopback.py @@ -16,17 +16,24 @@ from openpilot.selfdrive.pandad import can_list_to_can_capnp from openpilot.selfdrive.test.helpers import with_processes +def publish_device_state(pm, started): + msg = messaging.new_message('deviceState') + msg.deviceState.started = started + pm.send('deviceState', msg) + @retry(attempts=3) def setup_pandad(): params = Params() params.clear_all() - params.put_bool("IsOnroad", False) + pm = messaging.PubMaster(['deviceState']) sm = messaging.SubMaster(['pandaStates']) + publish_device_state(pm, False) with Timeout(90, "pandad didn't start"): while sm.recv_frame['pandaStates'] < 1 or len(sm['pandaStates']) == 0 or \ any(ps.pandaType == log.PandaState.PandaType.unknown for ps in sm['pandaStates']): - sm.update(1000) + publish_device_state(pm, False) + sm.update(100) # pandad safety setting relies on these params cp = car.CarParams.new_message() @@ -35,14 +42,15 @@ def setup_pandad(): safety_config.safetyModel = car.CarParams.SafetyModel.allOutput cp.safetyConfigs = [safety_config] - params.put_bool("IsOnroad", True) - params.put_bool("FirmwareQueryDone", True) - params.put_bool("ControlsReady", True) - params.put("CarParams", cp.to_bytes()) + params.put_bool("FirmwareQueryDone", True, block=True) + params.put_bool("ControlsReady", True, block=True) + params.put("CarParams", cp.to_bytes(), block=True) + publish_device_state(pm, True) with Timeout(90, "pandad didn't set safety mode"): while any(ps.safetyModel != car.CarParams.SafetyModel.allOutput for ps in sm['pandaStates']): - sm.update(1000) + publish_device_state(pm, True) + sm.update(100) def send_random_can_messages(sendcan, count): sent_msgs = defaultdict(set) diff --git a/selfdrive/selfdrived/alertmanager.py b/selfdrive/selfdrived/alertmanager.py index 34db27c7a4..c148c62d32 100644 --- a/selfdrive/selfdrived/alertmanager.py +++ b/selfdrive/selfdrived/alertmanager.py @@ -18,7 +18,7 @@ def set_offroad_alert(alert: str, show_alert: bool, extra_text: str | None = Non if show_alert: a = copy.copy(OFFROAD_ALERTS[alert]) a['extra'] = extra_text or '' - Params().put(alert, a) + Params().put(alert, a, block=True) else: Params().remove(alert) diff --git a/selfdrive/selfdrived/selfdrived.py b/selfdrive/selfdrived/selfdrived.py index 1a10d91cd7..30605d0a27 100755 --- a/selfdrive/selfdrived/selfdrived.py +++ b/selfdrive/selfdrived/selfdrived.py @@ -45,6 +45,8 @@ LaneChangeDirection = log.LaneChangeDirection EventName = log.OnroadEvent.EventName ButtonType = car.CarState.ButtonEvent.Type SafetyModel = car.CarParams.SafetyModel +AlertLevel = log.DriverMonitoringState.AlertLevel +MonitoringPolicy = log.DriverMonitoringState.MonitoringPolicy TurnDirection = custom.ModelDataV2SP.TurnDirection IGNORED_SAFETY_MODES = (SafetyModel.silent, SafetyModel.noOutput) @@ -140,6 +142,8 @@ class SelfdriveD(CruiseHelper): self.params ) self.recalibrating_seen = False + self.dm_lockout_set = False + self.dm_uncertain_alerted = False self.state_machine = StateMachine() self.rk = Ratekeeper(100, print_delay_threshold=None) @@ -216,8 +220,27 @@ class SelfdriveD(CruiseHelper): if not self.CP.pcmCruise and CS.vCruise > 250 and resume_pressed: self.events.add(EventName.resumeBlocked) + # Handle DM if not self.CP.notCar: - self.events.add_from_msg(self.sm['driverMonitoringState'].events) + # Block engaging until ignition cycle after max number or time of distractions + if self.sm['driverMonitoringState'].lockout and not self.dm_lockout_set: + self.params.put_bool("DriverTooDistracted", True) + self.dm_lockout_set = True + # No entry conditions + if self.sm['driverMonitoringState'].lockout or self.sm['driverMonitoringState'].alwaysOnLockout: + self.events.add(EventName.tooDistracted) + # Alerts + vision_dm = self.sm['driverMonitoringState'].activePolicy == MonitoringPolicy.vision + if self.sm['driverMonitoringState'].alertLevel == AlertLevel.one: + self.events.add(EventName.driverDistracted1 if vision_dm else EventName.driverUnresponsive1) + elif self.sm['driverMonitoringState'].alertLevel == AlertLevel.two: + self.events.add(EventName.driverDistracted2 if vision_dm else EventName.driverUnresponsive2) + elif self.sm['driverMonitoringState'].alertLevel == AlertLevel.three: + self.events.add(EventName.driverDistracted3 if vision_dm else EventName.driverUnresponsive3) + # Warn consistent DM uncertainty + if self.sm['driverMonitoringState'].visionPolicyState.uncertainOffroadAlertPercent >= 100 and not self.dm_uncertain_alerted: + set_offroad_alert("Offroad_DriverMonitoringUncertain", True) + self.dm_uncertain_alerted = True self.events_sp.add_from_msg(self.sm['longitudinalPlanSP'].events) # Add car events, ignore if CAN isn't valid @@ -241,7 +264,7 @@ class SelfdriveD(CruiseHelper): self.events.add(EventName.pedalPressed) # Create events for temperature, disk space, and memory - if self.sm['deviceState'].thermalStatus >= ThermalStatus.red: + if self.sm['deviceState'].thermalStatus >= ThermalStatus.overheated: self.events.add(EventName.overheat) if self.sm['deviceState'].freeSpacePercent < 7 and not SIMULATION: self.events.add(EventName.outOfSpace) @@ -440,7 +463,7 @@ class SelfdriveD(CruiseHelper): # TODO: fix simulator if not SIMULATION or REPLAY: - if self.sm['modelV2'].frameDropPerc > 20: + if self.sm['modelV2'].frameDropPerc > 1: self.events.add(EventName.modeldLagging) # mute canBusMissing event if in Park, as it sometimes may trigger a false alarm with MADS in Paused state @@ -454,7 +477,7 @@ class SelfdriveD(CruiseHelper): if any(not be.pressed and be.type == ButtonType.gapAdjustCruise for be in CS.buttonEvents): if not self.experimental_mode_switched: self.personality = (self.personality - 1) % 3 - self.params.put_nonblocking('LongitudinalPersonality', self.personality) + self.params.put('LongitudinalPersonality', self.personality) self.events.add(EventName.personalityChanged) self.experimental_mode_switched = False diff --git a/selfdrive/selfdrived/tests/test_alerts.py b/selfdrive/selfdrived/tests/test_alerts.py index a1867f2289..4cad9990be 100644 --- a/selfdrive/selfdrived/tests/test_alerts.py +++ b/selfdrive/selfdrived/tests/test_alerts.py @@ -63,7 +63,7 @@ class TestAlerts: for alert in ALERTS: if not isinstance(alert, Alert): - alert = alert(self.CP, self.CS, self.sm, metric=False, soft_disable_time=100, personality=log.LongitudinalPersonality.standard) + alert = alert(self.CP, self.CS, self.sm, False, 100, log.LongitudinalPersonality.standard) # for full size alerts, both text fields wrap the text, # so it's unlikely that they would go past the max width diff --git a/selfdrive/test/helpers.py b/selfdrive/test/helpers.py index 5dfc1c3ec8..49a8ec60a3 100644 --- a/selfdrive/test/helpers.py +++ b/selfdrive/test/helpers.py @@ -18,15 +18,15 @@ def set_params_enabled(): os.environ['LOGPRINT'] = "debug" params = Params() - params.put("HasAcceptedTerms", terms_version) - params.put("CompletedTrainingVersion", training_version) - params.put_bool("OpenpilotEnabledToggle", True) + params.put("HasAcceptedTerms", terms_version, block=True) + params.put("CompletedTrainingVersion", training_version, block=True) + params.put_bool("OpenpilotEnabledToggle", True, block=True) # valid calib msg = messaging.new_message('liveCalibration') msg.liveCalibration.validBlocks = 20 msg.liveCalibration.rpyCalib = [0.0, 0.0, 0.0] - params.put("CalibrationParams", msg.to_bytes()) + params.put("CalibrationParams", msg.to_bytes(), block=True) def release_only(f): @wraps(f) diff --git a/selfdrive/test/longitudinal_maneuvers/plant.py b/selfdrive/test/longitudinal_maneuvers/plant.py index e82ef2f65e..1431e60019 100755 --- a/selfdrive/test/longitudinal_maneuvers/plant.py +++ b/selfdrive/test/longitudinal_maneuvers/plant.py @@ -144,6 +144,8 @@ class Plant: 'gpsLocation': gps_data.gpsLocation} self.planner.update(sm) self.acceleration = self.planner.output_a_target + if self.planner.output_should_stop: + self.acceleration = min(-0.5, self.acceleration) self.speed = self.speed + self.acceleration * self.ts self.should_stop = self.planner.output_should_stop fcw = self.planner.fcw diff --git a/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py b/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py index 90bc46b187..b8f97c5041 100644 --- a/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py +++ b/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py @@ -170,7 +170,7 @@ def create_maneuvers(kwargs): initial_speed=0., lead_relevancy=True, initial_distance_lead=STOP_DISTANCE, - speed_lead_values=[0., 0., 2.], + speed_lead_values=[0., 0., 7.], breakpoints=[1., 10., 15.], ensure_start=True, **kwargs, diff --git a/selfdrive/test/process_replay/migration.py b/selfdrive/test/process_replay/migration.py index 278c366609..09fdb40b67 100644 --- a/selfdrive/test/process_replay/migration.py +++ b/selfdrive/test/process_replay/migration.py @@ -14,7 +14,7 @@ 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, CONTROL_N_T_IDX +from openpilot.selfdrive.controls.lib.drive_helpers import CONTROL_N, get_accel_from_plan from openpilot.system.manager.process_config import managed_processes from openpilot.tools.lib.logreader import LogIterable @@ -89,6 +89,10 @@ def migrate(lr: LogIterable, migration_funcs: list[MigrationFunc]): return lr +def as_reader(builder) -> capnp.lib.capnp._DynamicStructReader: + return log.Event.from_bytes(builder.to_bytes()).__enter__() # round-trip through bytes, 2x faster and 30x less memory than builder.as_reader() + + def migration(inputs: list[str], product: str|None=None): def decorator(func): @functools.wraps(func) @@ -124,9 +128,9 @@ 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, CONTROL_N_T_IDX) + a_target, should_stop = get_accel_from_plan(msg.longitudinalPlan.speeds, msg.longitudinalPlan.accels, ModelConstants.T_IDXS[:CONTROL_N]) new_msg.longitudinalPlan.aTarget, new_msg.longitudinalPlan.shouldStop = float(a_target), bool(should_stop) - ops.append((index, new_msg.as_reader())) + ops.append((index, as_reader(new_msg))) return ops, [], [] @@ -135,7 +139,7 @@ def migrate_driverAssistance(msgs): add_ops = [] for _, msg in msgs: new_msg = messaging.new_message('driverAssistance', valid=True, logMonoTime=msg.logMonoTime) - add_ops.append(new_msg.as_reader()) + add_ops.append(as_reader(new_msg)) return [], add_ops, [] @@ -152,7 +156,7 @@ def migrate_drivingModelData(msgs): fill_lane_line_meta(dmd.drivingModelData.laneLineMeta, msg.modelV2.laneLines, msg.modelV2.laneLineProbs) if all(len(a) for a in [msg.modelV2.position.x, msg.modelV2.position.y, msg.modelV2.position.z]): fill_xyz_poly(dmd.drivingModelData.path, ModelConstants.POLY_PATH_DEGREE, msg.modelV2.position.x, msg.modelV2.position.y, msg.modelV2.position.z) - add_ops.append( dmd.as_reader()) + add_ops.append(as_reader(dmd)) return [], add_ops, [] @@ -177,7 +181,7 @@ def migrate_liveTracks(msgs): pts.append(pt) new_msg.liveTracks.points = pts - ops.append((index, new_msg.as_reader())) + ops.append((index, as_reader(new_msg))) return ops, [], [] @@ -197,7 +201,7 @@ def migrate_liveLocationKalman(msgs): lp_field.valid = llk_field.valid for flag in ["inputsOK", "posenetOK", "sensorsOK"]: setattr(m.livePose, flag, getattr(msg.liveLocationKalmanDEPRECATED, flag)) - ops.append((index, m.as_reader())) + ops.append((index, as_reader(m))) return ops, [], [] @@ -212,7 +216,7 @@ def migrate_livePose(msgs): if msg.which() == "livePose": new_msg = msg.as_builder() new_msg.livePose.timestamp = msg.logMonoTime - ops.append((index, new_msg.as_reader())) + ops.append((index, as_reader(new_msg))) return ops, [], [] @@ -228,7 +232,7 @@ def migrate_controlsState(msgs): "alertStatus", "alertSize", "alertType", "experimentalMode", "personality"): setattr(ss, field, getattr(msg.controlsState.deprecated, field)) - add_ops.append(m.as_reader()) + add_ops.append(as_reader(m)) return [], add_ops, [] @@ -244,7 +248,7 @@ def migrate_carState(msgs): msg = msg.as_builder() msg.carState.vCruise = last_cs.controlsState.deprecated.vCruise msg.carState.vCruiseCluster = last_cs.controlsState.deprecated.vCruiseCluster - ops.append((index, msg.as_reader())) + ops.append((index, as_reader(msg))) return ops, [], [] @@ -254,7 +258,7 @@ def migrate_managerState(msgs): for index, msg in msgs: new_msg = msg.as_builder() new_msg.managerState.processes = [{'name': name, 'running': True} for name in managed_processes] - ops.append((index, new_msg.as_reader())) + ops.append((index, as_reader(new_msg))) return ops, [], [] @@ -267,7 +271,7 @@ def migrate_gpsLocation(msgs): # hasFix is a newer field if not g.hasFix and g.flags == 1: g.hasFix = True - ops.append((index, new_msg.as_reader())) + ops.append((index, as_reader(new_msg))) return ops, [], [] @@ -283,7 +287,7 @@ def migrate_deviceState(msgs): if msg.which() == 'deviceState': n = msg.as_builder() n.deviceState.deviceType = init_data.deviceType - ops.append((i, n.as_reader())) + ops.append((i, as_reader(n))) return ops, [], [] @@ -295,7 +299,7 @@ def migrate_carOutput(msgs): co.valid = msg.valid co.logMonoTime = msg.logMonoTime co.carOutput.actuatorsOutput = msg.carControl.actuatorsOutputDEPRECATED - add_ops.append(co.as_reader()) + add_ops.append(as_reader(co)) return [], add_ops, [] @@ -333,13 +337,13 @@ def migrate_pandaStates(msgs): new_msg.logMonoTime = msg.logMonoTime new_msg.pandaStates[0] = msg.pandaStateDEPRECATED new_msg.pandaStates[0].safetyParam = safety_param - ops.append((index, new_msg.as_reader())) + ops.append((index, as_reader(new_msg))) 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())) + ops.append((index, as_reader(new_msg))) return ops, [], [] @@ -354,7 +358,7 @@ def migrate_peripheralState(msgs): new_msg = messaging.new_message("peripheralState") new_msg.valid = msg.valid new_msg.logMonoTime = msg.logMonoTime - add_ops.append(new_msg.as_reader()) + add_ops.append(as_reader(new_msg)) return [], add_ops, [] @@ -409,7 +413,7 @@ def migrate_cameraStates(msgs): new_msg.valid = msg.valid del_ops.append(index) - add_ops.append(new_msg.as_reader()) + add_ops.append(as_reader(new_msg)) return [], add_ops, del_ops @@ -421,7 +425,7 @@ def migrate_carParams(msgs): CP.carParams.carFingerprint = MIGRATION.get(CP.carParams.carFingerprint, CP.carParams.carFingerprint) for car_fw in CP.carParams.carFw: car_fw.brand = CP.carParams.brand - ops.append((index, CP.as_reader())) + ops.append((index, as_reader(CP))) return ops, [], [] @@ -449,14 +453,11 @@ def migrate_sensorEvents(msgs): m.logMonoTime = msg.logMonoTime m_dat = getattr(m, sensor_service) - m_dat.version = evt.version - m_dat.sensor = evt.sensor - m_dat.type = evt.type m_dat.source = evt.source m_dat.timestamp = evt.timestamp setattr(m_dat, evt.which(), getattr(evt, evt.which())) - add_ops.append(m.as_reader()) + add_ops.append(as_reader(m)) del_ops.append(index) return [], add_ops, del_ops @@ -479,27 +480,51 @@ def migrate_onroadEvents(msgs): new_msg.valid = msg.valid new_msg.logMonoTime = msg.logMonoTime new_msg.onroadEvents = onroadEvents - ops.append((index, new_msg.as_reader())) + ops.append((index, as_reader(new_msg))) return ops, [], [] -@migration(inputs=["driverMonitoringState"]) +@migration(inputs=["driverMonitoringStateDEPRECATED"]) def migrate_driverMonitoringState(msgs): ops = [] for index, msg in msgs: - msg = msg.as_builder() - events = [] - for event in msg.driverMonitoringState.deprecated.events: - try: - if not str(event.name).endswith('DEPRECATED'): - migrated_event = migrate_onroad_event(event) - if migrated_event is not None: - events.append(migrated_event) - except RuntimeError: # Member was null - traceback.print_exc() + old = msg.driverMonitoringStateDEPRECATED + new_msg = messaging.new_message('driverMonitoringState', valid=msg.valid, logMonoTime=msg.logMonoTime) + dm = new_msg.driverMonitoringState + dm.isRHD = old.isRHD + dm.activePolicy = log.DriverMonitoringState.MonitoringPolicy.vision if old.isActiveMode else \ + log.DriverMonitoringState.MonitoringPolicy.wheeltouch - msg.driverMonitoringState.events = events - ops.append((index, msg.as_reader())) + AlertLevel = log.DriverMonitoringState.AlertLevel + event_to_alert_level = { + 'driverDistracted1': AlertLevel.one, 'driverUnresponsive1': AlertLevel.one, + 'driverDistracted2': AlertLevel.two, 'driverUnresponsive2': AlertLevel.two, + 'driverDistracted3': AlertLevel.three, 'driverUnresponsive3': AlertLevel.three, + } + for event in old.events: + level = event_to_alert_level.get(str(event.name)) + if level is not None: + dm.alertLevel = level + break + dm.lockout = any(str(event.name) == 'tooDistracted' for event in old.events) + + dm.visionPolicyState.awarenessPercent = int(max(0, min(100, (old.awarenessStatus if old.isActiveMode else old.awarenessActive) * 100))) + dm.visionPolicyState.awarenessStep = old.stepChange if old.isActiveMode else 0. + dm.visionPolicyState.isDistracted = old.isDistracted + dm.visionPolicyState.distractedTypes.pose = bool(old.distractedType & 1) + dm.visionPolicyState.distractedTypes.eye = bool(old.distractedType & 2) + dm.visionPolicyState.distractedTypes.phone = bool(old.distractedType & 4) + dm.visionPolicyState.faceDetected = old.faceDetected + dm.visionPolicyState.pose.pitchCalib.offset = old.posePitchOffset + dm.visionPolicyState.pose.pitchCalib.calibratedPercent = int(min(100, old.posePitchValidCount / 1200 * 100)) + dm.visionPolicyState.pose.yawCalib.offset = old.poseYawOffset + dm.visionPolicyState.pose.yawCalib.calibratedPercent = int(min(100, old.poseYawValidCount / 1200 * 100)) + dm.visionPolicyState.pose.calibrated = old.posePitchValidCount >= 1200 and old.poseYawValidCount >= 1200 + dm.visionPolicyState.wheeltouchFallbackPercent = int(min(100, old.hiStdCount / 200 * 100)) + dm.visionPolicyState.uncertainOffroadAlertPercent = int(min(100, old.uncertainCount / 1200 * 100)) + dm.wheeltouchPolicyState.awarenessPercent = int(max(0, min(100, (old.awarenessPassive if old.isActiveMode else old.awarenessStatus) * 100))) + dm.wheeltouchPolicyState.awarenessStep = 0. if old.isActiveMode else old.stepChange + ops.append((index, as_reader(new_msg))) return ops, [], [] diff --git a/selfdrive/test/process_replay/model_replay.py b/selfdrive/test/process_replay/model_replay.py index a6ccaa1047..266f66aaf2 100755 --- a/selfdrive/test/process_replay/model_replay.py +++ b/selfdrive/test/process_replay/model_replay.py @@ -35,7 +35,7 @@ GITHUB = GithubUtils(API_TOKEN, DATA_TOKEN) EXEC_TIMINGS = [ # model, instant max, average max ("modelV2", 0.05, 0.028), - ("driverStateV2", 0.05, 0.016), + ("driverStateV2", 0.05, 0.018), ] def get_log_fn(test_route, ref="master"): diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 65587d44b1..77254cecee 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -192,9 +192,9 @@ class ProcessContainer: params = Params() for k, v in params_config.items(): if isinstance(v, bool): - params.put_bool(k, v) + params.put_bool(k, v, block=True) else: - params.put(k, v) + params.put(k, v, block=True) self.environ_config = environ_config @@ -375,8 +375,8 @@ def get_car_params_callback(rc, pm, msgs, fingerprint): _CI = get_car(can_recv, lambda _msgs: None, lambda obd: None, params.get_bool("AlphaLongitudinalEnabled"), False, cached_params=cached_params) CP, CP_SP = _CI.CP, _CI.CP_SP - params.put("CarParams", CP.to_bytes()) - params.put("CarParamsSP", convert_to_capnp(CP_SP).to_bytes()) + params.put("CarParams", CP.to_bytes(), block=True) + params.put("CarParamsSP", convert_to_capnp(CP_SP).to_bytes(), block=True) def card_rcv_callback(msg, cfg, frame): diff --git a/selfdrive/test/scons_build_test.sh b/selfdrive/test/scons_build_test.sh index 5ffdb4379e..d4a0733569 100755 --- a/selfdrive/test/scons_build_test.sh +++ b/selfdrive/test/scons_build_test.sh @@ -13,7 +13,7 @@ cd $BASEDIR cd $BASEDIR/opendbc_repo/ scons --clean -scons --no-cache --random -j$(nproc) +scons --no-cache --random if ! scons -q; then echo "FAILED: all build products not up to date after first pass." exit 1 diff --git a/selfdrive/test/setup_device_ci.sh b/selfdrive/test/setup_device_ci.sh index 2a1442a20c..3fe353e72c 100755 --- a/selfdrive/test/setup_device_ci.sh +++ b/selfdrive/test/setup_device_ci.sh @@ -48,13 +48,6 @@ while true; do if ! sudo systemctl is-active -q ssh; then sudo systemctl start ssh fi - - #if ! pgrep -f 'ciui.py' > /dev/null 2>&1; then - # echo 'starting UI' - # cp $SOURCE_DIR/selfdrive/test/ciui.py /data/ - # /data/ciui.py & - #fi - sleep 5s done diff --git a/selfdrive/test/setup_xvfb.sh b/selfdrive/test/setup_xvfb.sh index c1b74a850e..50b313658d 100755 --- a/selfdrive/test/setup_xvfb.sh +++ b/selfdrive/test/setup_xvfb.sh @@ -9,7 +9,7 @@ else fi export DISPLAY=:$DISP_ID -sudo Xvfb $DISPLAY -screen 0 2160x1080x24 2>/dev/null & +Xvfb $DISPLAY -screen 0 2160x1080x24 2>/dev/null & # check for x11 socket for the specified display ID while [ ! -S /tmp/.X11-unix/X$DISP_ID ] diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index 1129a1a2ff..8161dca130 100644 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -68,6 +68,7 @@ PROCS = { "system.loggerd.deleter": 1.0, "./pandad": 19.0, "system.qcomgpsd.qcomgpsd": 1.0, + "system.hardware.tici.modem": 10.0, } TIMINGS = { @@ -118,7 +119,7 @@ class TestOnroad: # setup env params = Params() params.remove("CurrentRoute") - params.put_bool("RecordFront", True) + params.put_bool("RecordFront", True, block=True) set_params_enabled() os.environ['REPLAY'] = '1' os.environ['MSGQ_PREALLOC'] = '1' @@ -209,7 +210,7 @@ class TestOnroad: # other processes preempt ui while starting up offset = int(20 * LOG_OFFSET) - ts = self.ts['uiDebug']['drawTimeMillis'][offset:] + ts = self.ts['uiDebug']['cpuTimeMillis'][offset:] result += f"min {min(ts):.2f}ms\n" result += f"max {max(ts):.2f}ms\n" result += f"std {np.std(ts):.2f}ms\n" @@ -370,23 +371,6 @@ class TestOnroad: assert enc_sof == cam_sof, f"SOF mismatch: frameId={fid}, enc_sof={enc_sof}, cam_sof={cam_sof}" assert enc_eof == cam_eof, f"EOF mismatch: frameId={fid}, enc_eof={enc_eof}, cam_eof={cam_eof}" - def test_mpc_execution_timings(self): - result = "\n" - result += "------------------------------------------------\n" - result += "----------------- MPC Timing ------------------\n" - result += "------------------------------------------------\n" - - cfgs = [("longitudinalPlan", 0.05, 0.05),] - for (s, instant_max, avg_max) in cfgs: - ts = [getattr(m, s).solverExecutionTime for m in self.msgs[s]] - assert max(ts) < instant_max, f"high '{s}' execution time: {max(ts)}" - assert np.mean(ts) < avg_max, f"high avg '{s}' execution time: {np.mean(ts)}" - result += f"'{s}' execution time: min {min(ts):.5f}s\n" - result += f"'{s}' execution time: max {max(ts):.5f}s\n" - result += f"'{s}' execution time: mean {np.mean(ts):.5f}s\n" - result += "------------------------------------------------\n" - print(result) - def test_model_execution_timings(self, subtests): result = "\n" result += "------------------------------------------------\n" @@ -401,9 +385,7 @@ class TestOnroad: ("driverStateV2", 0.3, 0.05), ] for (s, instant_max, avg_max) in cfgs: - ts = [getattr(m, s).modelExecutionTime for m in self.msgs[s]] - # TODO some init can happen in first iteration - ts = ts[1:] + ts = [getattr(m, s).modelExecutionTime for m in self.msgs[s] if (m.logMonoTime*1e-9 - self.ts[s]['t'][0]) > LOG_OFFSET] result += f"'{s}' execution time: min {min(ts):.5f}s\n" result += f"'{s}' execution time: max {max(ts):.5f}s\n" result += f"'{s}' execution time: mean {np.mean(ts):.5f}s\n" diff --git a/selfdrive/test/test_updated.py b/selfdrive/test/test_updated.py index 95365640f5..e4cc714b87 100644 --- a/selfdrive/test/test_updated.py +++ b/selfdrive/test/test_updated.py @@ -50,7 +50,7 @@ class TestUpdated: f"git clone {BASEDIR} {self.git_remote_dir}", f"git clone {self.git_remote_dir} {self.basedir}", f"cd {self.basedir} && git submodule init && git submodule update", - f"cd {self.basedir} && scons -j{os.cpu_count()} cereal/ common/" + f"cd {self.basedir} && scons cereal/ common/" ]) self.params = Params(os.path.join(self.basedir, "persist/params")) @@ -92,7 +92,7 @@ class TestUpdated: return subprocess.Popen(updated_path, env=os.environ) def _start_updater(self, offroad=True, nosleep=False): - self.params.put_bool("IsOffroad", offroad) + self.params.put_bool("IsOffroad", offroad, block=True) self.updated_proc = self._get_updated_proc() if not nosleep: time.sleep(1) diff --git a/selfdrive/ui/SConscript b/selfdrive/ui/SConscript index 1a662e6b24..3d668aef8f 100644 --- a/selfdrive/ui/SConscript +++ b/selfdrive/ui/SConscript @@ -1,4 +1,6 @@ from pathlib import Path +import importlib.util + Import('env', 'arch', 'common') # build the fonts @@ -18,15 +20,13 @@ env.Command( if GetOption('extras') and arch == "larch64": # build installers + raylib_dir = Path(importlib.util.find_spec("raylib").submodule_search_locations[0]) / "install" raylib_env = env.Clone() - raylib_env['LIBPATH'] += [f'#third_party/raylib/{arch}/'] + raylib_env['CPPPATH'] += [str(raylib_dir / "include")] + raylib_env['LIBPATH'] += [str(raylib_dir / "lib")] raylib_env['LINKFLAGS'].append('-Wl,-strip-debug') - raylib_libs = common + ["raylib"] - if arch == "larch64": - raylib_libs += ["GLESv2", "EGL", "gbm", "drm"] - else: - raylib_libs += ["GL"] + raylib_libs = common + ["raylib_comma", "GLESv2", "EGL", "gbm", "drm"] release = "release3" installers = [ diff --git a/selfdrive/ui/body/__init__.py b/selfdrive/ui/body/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/selfdrive/ui/body/animations.py b/selfdrive/ui/body/animations.py new file mode 100644 index 0000000000..c40f7ecdef --- /dev/null +++ b/selfdrive/ui/body/animations.py @@ -0,0 +1,278 @@ +from dataclasses import dataclass +from enum import Enum +import time + + +class AnimationMode(Enum): + ONCE_FORWARD = 1 + ONCE_FORWARD_BACKWARD = 2 + REPEAT_FORWARD = 3 + REPEAT_FORWARD_BACKWARD = 4 + + +@dataclass +class Animation: + frames: list[list[tuple[int, int]]] + starting_frames: list[list[tuple[int, int]]] | None = None # played once before the main loop + frame_duration: float = 0.15 # seconds each frame is shown + mode: AnimationMode = AnimationMode.REPEAT_FORWARD_BACKWARD + repeat_interval: float = 5.0 # seconds between animation restarts (only for REPEAT modes) + hold_end: float = 0.0 # seconds to hold the last frame before playing backward (only for *_BACKWARD modes) + left_turn_remove: list[tuple[int, int]] | None = None # dots to remove from frame when turning left + right_turn_remove: list[tuple[int, int]] | None = None # dots to remove from frame when turning right + + +# --- Animation Helper Functions --- + +def _mirror(dots: list[tuple[int, int]]) -> list[tuple[int, int]]: + """Mirror a component from the left side of the face to the right""" + return [(r, 15 - c) for r, c in dots] + + +def _mirror_no_flip(dots: list[tuple[int, int]]) -> list[tuple[int, int]]: + """Move a component to the mirrored position on the right half without flipping its shape.""" + min_c = min(c for _, c in dots) + max_c = max(c for _, c in dots) + return [(r, 15 - max_c - min_c + c) for r, c in dots] + + +def _shift(dots: list[tuple[int, int]], rc: tuple[int, int]) -> list[tuple[int, int]]: + dr, dc = rc + return [(r + dr, c + dc) for r, c in dots] + + +def _make_frame(left_eye: list[tuple[int, int]], right_eye: list[tuple[int, int]], + left_brow: list[tuple[int, int]], right_brow: list[tuple[int, int]], + mouth: list[tuple[int, int]]) -> list[tuple[int, int]]: + return left_eye + left_brow + right_eye + right_brow + mouth + + +# --- Animation Helper Components --- + +# Eyes (left side) +EYE_OPEN = [ + (2, 2), (2, 3), +(3, 1), (3, 2), (3, 3), (3, 4), +(4, 1), (4, 2), (4, 3), (4, 4), + (5, 2), (5, 3) +] +EYE_HALF = [ +(4, 1), (4, 2), (4, 3), (4, 4), + (5, 2), (5, 3) +] +EYE_CLOSED = [ +(4, 1), (4, 4), + (5, 2), (5, 3), +] +EYE_LEFT_LOOK = [ + (2, 2), (2, 3), +(3, 1), (3, 2), +(4, 1), (4, 2), + (5, 2), (5, 3), +] +EYE_RIGHT_LOOK = [ + (2, 2), (2, 3), + (3, 3), (3, 4), + (4, 3), (4, 4), + (5, 2), (5, 3), +] + +# Eyebrows (left side) +BROW_HIGH = [ + (0, 1), (0, 2), +(1, 0), +] +BROW_LOWERED = [ + (1, 1), (1, 2), +(2, 0) +] +BROW_STRAIGHT = [(1, 0), (1, 1), (1, 2)] +BROW_DOWN = [ +(0, 1), (0, 2), + (1, 3) +] + +# Mouths (centered, not mirrored) +MOUTH_SMILE = [ +(6, 6), (6, 9), + (7, 7), (7, 8), +] +MOUTH_NORMAL = [(7, 7), (7, 8)] +MOUTH_SAD = [ + (6, 7), (6, 8), +(7, 6), (7, 9) +] + +# --- Animations --- + +NORMAL = Animation( + frames=[ + _make_frame(EYE_OPEN, _mirror(EYE_OPEN), BROW_HIGH, _mirror(BROW_HIGH), MOUTH_SMILE), + _make_frame(EYE_HALF, _mirror(EYE_HALF), BROW_HIGH, _mirror(BROW_HIGH), MOUTH_SMILE), + _make_frame(EYE_CLOSED, _mirror(EYE_CLOSED), BROW_LOWERED, _mirror(BROW_LOWERED), MOUTH_SMILE), + ], + left_turn_remove=[ + (3, 3), (3, 4), + (4, 3), (4, 4), + ] + _mirror_no_flip([ + (3, 1), (3, 2), + (4, 1), (4, 2), + ]), + right_turn_remove=[ + (3, 1), (3, 2), + (4, 1), (4, 2), + ] + _mirror_no_flip([ + (3, 3), (3, 4), + (4, 3), (4, 4), + ]) +) + +ASLEEP = Animation( + frames=[ + _make_frame(EYE_CLOSED, _mirror(EYE_CLOSED), [], [], MOUTH_NORMAL), + ], +) + +SLEEPY = Animation( + frames=[ + _make_frame(EYE_CLOSED, _mirror(EYE_CLOSED), _shift(BROW_STRAIGHT, (1, 0)), [], MOUTH_NORMAL), + _make_frame(EYE_HALF, _mirror(EYE_CLOSED), BROW_LOWERED, [], MOUTH_NORMAL), + _make_frame(EYE_OPEN, _mirror(EYE_CLOSED), BROW_HIGH, [], MOUTH_NORMAL) + ], + frame_duration=0.25, + mode=AnimationMode.ONCE_FORWARD_BACKWARD, + repeat_interval=10, + hold_end=1.5, +) + +INQUISITIVE = Animation( + frames=[ + _make_frame(EYE_OPEN, _mirror(EYE_OPEN), BROW_HIGH, _mirror(BROW_HIGH), MOUTH_SMILE), + + _make_frame(EYE_LEFT_LOOK, _mirror(EYE_RIGHT_LOOK), BROW_HIGH, _mirror(BROW_HIGH), MOUTH_SMILE), + _make_frame(_shift(EYE_LEFT_LOOK, (0, -1)), _shift(_mirror(EYE_RIGHT_LOOK), (0, -1)), BROW_HIGH, _mirror(BROW_HIGH), MOUTH_SMILE), + _make_frame(_shift(EYE_LEFT_LOOK, (0, -1)), _shift(_mirror(EYE_RIGHT_LOOK), (0, -1)), BROW_HIGH, _mirror(BROW_HIGH), MOUTH_SMILE), + _make_frame(_shift(EYE_LEFT_LOOK, (0, -1)), _shift(_mirror(EYE_RIGHT_LOOK), (0, -1)), BROW_HIGH, _mirror(BROW_HIGH), MOUTH_SMILE), + _make_frame(EYE_LEFT_LOOK, _mirror(EYE_RIGHT_LOOK), BROW_HIGH, _mirror(BROW_HIGH), MOUTH_SMILE), + + _make_frame(EYE_RIGHT_LOOK, _mirror(EYE_LEFT_LOOK), BROW_HIGH, _mirror(BROW_HIGH), MOUTH_SMILE), + _make_frame(_shift(EYE_RIGHT_LOOK, (0, 1)), _shift(_mirror(EYE_LEFT_LOOK), (0, 1)), BROW_HIGH, _mirror(BROW_HIGH), MOUTH_SMILE), + _make_frame(_shift(EYE_RIGHT_LOOK, (0, 1)), _shift(_mirror(EYE_LEFT_LOOK), (0, 1)), BROW_HIGH, _mirror(BROW_HIGH), MOUTH_SMILE), + _make_frame(_shift(EYE_RIGHT_LOOK, (0, 1)), _shift(_mirror(EYE_LEFT_LOOK), (0, 1)), BROW_HIGH, _mirror(BROW_HIGH), MOUTH_SMILE), + _make_frame(EYE_RIGHT_LOOK, _mirror(EYE_LEFT_LOOK), BROW_HIGH, _mirror(BROW_HIGH), MOUTH_SMILE), + + _make_frame(EYE_OPEN, _mirror(EYE_OPEN), BROW_HIGH, _mirror(BROW_HIGH), MOUTH_SMILE), + ], + mode=AnimationMode.REPEAT_FORWARD, + frame_duration=0.15, + repeat_interval=10 +) + +WINK = Animation( + frames=[ + _make_frame(EYE_OPEN, _mirror(EYE_OPEN), BROW_HIGH, _mirror(BROW_HIGH), MOUTH_SMILE), + _make_frame(EYE_OPEN, _mirror(EYE_CLOSED), BROW_HIGH, _mirror(_shift(BROW_DOWN, (0, 2))), MOUTH_SMILE), + ], + mode=AnimationMode.ONCE_FORWARD_BACKWARD, + frame_duration=0.75, +) + + +# --- Face Animator Class --- + +class FaceAnimator: + def __init__(self, animation: Animation): + self._animation = animation + self._next: Animation | None = None + self._start_time = time.monotonic() + self._rewinding = False + self._rewind_start: float = 0.0 + self._rewind_from: int = 0 + self._seen_nonzero = False + + def set_animation(self, animation: Animation): + if animation is not self._animation: + self._next = animation + + def get_dots(self) -> list[tuple[int, int]]: + now = time.monotonic() + elapsed = now - self._start_time + + # Handle rewind for forward-only animations + if self._rewinding: + rewind_elapsed = now - self._rewind_start + frames_back = round(rewind_elapsed / self._animation.frame_duration) + frame_index = self._rewind_from - frames_back + if frame_index <= 0: + return self._switch_to_next(now) + return self._animation.frames[frame_index] + + # Play starting frames first (once) + starting = self._animation.starting_frames or [] + starting_duration = len(starting) * self._animation.frame_duration + if starting and elapsed < starting_duration: + frame_index = min(int(elapsed / self._animation.frame_duration), len(starting) - 1) + return starting[frame_index] + + # Main loop + loop_elapsed = elapsed - starting_duration if starting else elapsed + frame_index = _get_frame_index(self._animation, loop_elapsed, gap_first=bool(starting)) + + if frame_index != 0: + self._seen_nonzero = True + + if self._next is not None: + if frame_index == 0 and (len(self._animation.frames) == 1 or self._seen_nonzero): + return self._switch_to_next(now) + # No natural return to frame 0 — start rewinding + if self._animation.mode in (AnimationMode.ONCE_FORWARD, AnimationMode.REPEAT_FORWARD): + self._rewinding = True + self._rewind_start = now + self._rewind_from = frame_index + + return self._animation.frames[frame_index] + + def _switch_to_next(self, now: float) -> list[tuple[int, int]]: + self._animation = self._next + self._next = None + self._rewinding = False + self._seen_nonzero = False + self._start_time = now + return self._animation.frames[0] + + +def _get_frame_index(animation: Animation, elapsed: float, gap_first: bool = False) -> int: + """Get the current frame index given elapsed time and animation mode.""" + num_frames = len(animation.frames) + if num_frames == 1: + return 0 + + fd = animation.frame_duration + has_backward = animation.mode in (AnimationMode.ONCE_FORWARD_BACKWARD, AnimationMode.REPEAT_FORWARD_BACKWARD) + repeats = animation.mode in (AnimationMode.REPEAT_FORWARD, AnimationMode.REPEAT_FORWARD_BACKWARD) + + forward_duration = num_frames * fd + backward_frames = max(num_frames - 2, 0) if has_backward else 0 + hold = animation.hold_end if has_backward else 0.0 + cycle_duration = forward_duration + hold + backward_frames * fd + + if not repeats: + t = min(elapsed, cycle_duration) + else: + t = (elapsed + cycle_duration if gap_first else elapsed) % animation.repeat_interval + + # Forward phase + if t < forward_duration: + return min(int(t / fd), num_frames - 1) + t -= forward_duration + + # Hold at last frame + if t < hold: + return num_frames - 1 + t -= hold + + # Backward phase + if backward_frames and t < backward_frames * fd: + return num_frames - 2 - min(int(t / fd), backward_frames - 1) + + return 0 if has_backward else num_frames - 1 diff --git a/selfdrive/ui/body/layouts/__init__.py b/selfdrive/ui/body/layouts/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/selfdrive/ui/body/layouts/onroad.py b/selfdrive/ui/body/layouts/onroad.py new file mode 100644 index 0000000000..d7e9f419cc --- /dev/null +++ b/selfdrive/ui/body/layouts/onroad.py @@ -0,0 +1,93 @@ +import time +import pyray as rl + +from openpilot.system.ui.lib.application import gui_app, FontWeight +from openpilot.system.ui.widgets import Widget +from openpilot.system.ui.widgets.label import UnifiedLabel +from openpilot.selfdrive.ui.ui_state import ui_state +from openpilot.selfdrive.ui.body.animations import FaceAnimator, ASLEEP, INQUISITIVE, NORMAL, SLEEPY + +GRID_COLS = 16 +GRID_ROWS = 8 +DOT_RADIUS = 50 if gui_app.big_ui() else 10 + +IDLE_TIMEOUT = 30.0 # seconds of no joystick input before playing INQUISITIVE +IDLE_STEER_THRESH = 0.5 # degrees — below this counts as no input +IDLE_SPEED_THRESH = 0.01 # m/s — below this counts as no input + + +# This class is used both in BIG (tizi) and small (mici) UIs +class BodyLayout(Widget): + def __init__(self): + super().__init__() + self._animator = FaceAnimator(ASLEEP) + self._turning_left = False + self._turning_right = False + self._last_input_time = time.monotonic() + self._was_active = False + self._offroad_label = UnifiedLabel("turn on ignition to use", 95 if gui_app.big_ui() else 45, FontWeight.DISPLAY, + alignment=rl.GuiTextAlignment.TEXT_ALIGN_CENTER, + alignment_vertical=rl.GuiTextAlignmentVertical.TEXT_ALIGN_MIDDLE) + + def draw_dot_grid(self, rect: rl.Rectangle, dots: list[tuple[int, int]], color: rl.Color): + spacing = min(rect.height / GRID_ROWS, rect.width / GRID_COLS) + + grid_w = (GRID_COLS - 1) * spacing + grid_h = (GRID_ROWS - 1) * spacing + + offset_x = rect.x + (rect.width - grid_w) / 2 + offset_y = rect.y + (rect.height - grid_h) / 2 + + for row, col in dots: + x = int(offset_x + col * spacing) + y = int(offset_y + row * spacing) + rl.draw_circle(x, y, DOT_RADIUS, color) + + def _update_state(self): + super()._update_state() + + sm = ui_state.sm + + if ui_state.is_onroad(): + if not self._was_active: + self._last_input_time = time.monotonic() + self._was_active = True + + cs = sm['carState'] + has_input = abs(cs.steeringAngleDeg) > IDLE_STEER_THRESH or abs(cs.vEgo) > IDLE_SPEED_THRESH + if has_input: + self._last_input_time = time.monotonic() + + if time.monotonic() - self._last_input_time > IDLE_TIMEOUT: + self._animator.set_animation(INQUISITIVE) + else: + self._animator.set_animation(NORMAL) + else: + self._was_active = False + self._animator.set_animation(ASLEEP) + + steer = sm['testJoystick'].axes[1] if len(sm['testJoystick'].axes) > 1 else 0 + self._turning_left = steer <= -0.05 + self._turning_right = steer >= 0.05 + + # play animation on screen tap + def _handle_mouse_release(self, mouse_pos): + super()._handle_mouse_release(mouse_pos) + if not self._was_active: + self._animator.set_animation(SLEEPY) + + def _render(self, rect: rl.Rectangle): + dots = self._animator.get_dots() + animation = self._animator._animation + if self._turning_left and animation.left_turn_remove: + remove_set = set(animation.left_turn_remove) + dots = [d for d in dots if d not in remove_set] + elif self._turning_right and animation.right_turn_remove: + remove_set = set(animation.right_turn_remove) + dots = [d for d in dots if d not in remove_set] + self.draw_dot_grid(rect, dots, rl.WHITE) + + if ui_state.is_offroad(): + rl.draw_rectangle(int(self.rect.x), int(self.rect.y), int(self.rect.width), int(self.rect.height), rl.Color(0, 0, 0, 175)) + upper_half = rl.Rectangle(rect.x, rect.y, rect.width, rect.height / 2) + self._offroad_label.render(upper_half) diff --git a/selfdrive/ui/installer/installer.cc b/selfdrive/ui/installer/installer.cc index 0832fbb628..176c2d510f 100644 --- a/selfdrive/ui/installer/installer.cc +++ b/selfdrive/ui/installer/installer.cc @@ -6,7 +6,7 @@ #include "common/swaglog.h" #include "common/util.h" #include "system/hardware/hw.h" -#include "third_party/raylib/include/raylib.h" +#include "raylib.h" int freshClone(); int cachedFetch(const std::string &cache); diff --git a/selfdrive/ui/layouts/main.py b/selfdrive/ui/layouts/main.py index 2adecfeaa8..1e599f4ea7 100644 --- a/selfdrive/ui/layouts/main.py +++ b/selfdrive/ui/layouts/main.py @@ -2,13 +2,14 @@ import pyray as rl from enum import IntEnum import cereal.messaging as messaging from openpilot.system.ui.lib.application import gui_app +from openpilot.system.ui.widgets import Widget from openpilot.selfdrive.ui.layouts.sidebar import Sidebar, SIDEBAR_WIDTH from openpilot.selfdrive.ui.layouts.home import HomeLayout from openpilot.selfdrive.ui.layouts.settings.settings import SettingsLayout, PanelType from openpilot.selfdrive.ui.onroad.augmented_road_view import AugmentedRoadView from openpilot.selfdrive.ui.ui_state import device, ui_state -from openpilot.system.ui.widgets import Widget from openpilot.selfdrive.ui.layouts.onboarding import OnboardingWindow +from openpilot.selfdrive.ui.body.layouts.onroad import BodyLayout if gui_app.sunnypilot_ui(): from openpilot.selfdrive.ui.sunnypilot.layouts.settings.settings import SettingsLayoutSP as SettingsLayout @@ -31,7 +32,9 @@ class MainLayout(Widget): self._prev_onroad = False # Initialize layouts - self._layouts = {MainState.HOME: HomeLayout(), MainState.SETTINGS: SettingsLayout(), MainState.ONROAD: AugmentedRoadView()} + self._home_layout = HomeLayout() + self._home_body_layout = BodyLayout() + self._layouts = {MainState.HOME: self._home_layout, MainState.SETTINGS: SettingsLayout(), MainState.ONROAD: AugmentedRoadView()} self._sidebar_rect = rl.Rectangle(0, 0, 0, 0) self._content_rect = rl.Rectangle(0, 0, 0, 0) @@ -57,14 +60,18 @@ class MainLayout(Widget): self._layouts[MainState.HOME]._setup_widget.set_open_settings_callback(lambda: self.open_settings(PanelType.FIREHOSE)) self._layouts[MainState.HOME].set_settings_callback(lambda: self.open_settings(PanelType.TOGGLES)) self._layouts[MainState.SETTINGS].set_callbacks(on_close=self._set_mode_for_state) - self._layouts[MainState.ONROAD].set_click_callback(self._on_onroad_clicked) + + for layout in (self._layouts[MainState.ONROAD], self._home_body_layout): + layout.set_click_callback(self._on_onroad_clicked) + device.add_interactive_timeout_callback(self._set_mode_for_state) + ui_state.add_on_body_changed_callbacks(self._on_body_changed) def _update_layout_rects(self): self._sidebar_rect = rl.Rectangle(self._rect.x, self._rect.y, SIDEBAR_WIDTH, self._rect.height) x_offset = SIDEBAR_WIDTH if self._sidebar.is_visible else 0 - self._content_rect = rl.Rectangle(self._rect.y + x_offset, self._rect.y, self._rect.width - x_offset, self._rect.height) + self._content_rect = rl.Rectangle(self._rect.x + x_offset, self._rect.y, self._rect.width - x_offset, self._rect.height) def _handle_onroad_transition(self): if ui_state.started != self._prev_onroad: @@ -73,6 +80,12 @@ class MainLayout(Widget): self._set_mode_for_state() def _set_mode_for_state(self): + # Don't go onroad if body, home is onroad + if ui_state.is_body: + self._set_current_layout(MainState.HOME) + self._sidebar.set_visible(not ui_state.ignition) + return + if ui_state.started: # Don't hide sidebar from interactive timeout if self._current_mode != MainState.ONROAD: @@ -104,6 +117,10 @@ class MainLayout(Widget): def _on_onroad_clicked(self): self._sidebar.set_visible(not self._sidebar.is_visible) + def _on_body_changed(self): + self._layouts[MainState.HOME] = self._home_body_layout if ui_state.is_body else self._home_layout + self._set_mode_for_state() + def _render_main_content(self): # Render sidebar if self._sidebar.is_visible: diff --git a/selfdrive/ui/layouts/onboarding.py b/selfdrive/ui/layouts/onboarding.py index 452ed53c08..6e683c0922 100644 --- a/selfdrive/ui/layouts/onboarding.py +++ b/selfdrive/ui/layouts/onboarding.py @@ -69,7 +69,7 @@ class TrainingGuide(Widget): if self._step == DM_RECORD_STEP: yes = rl.check_collision_point_rec(mouse_pos, DM_RECORD_YES_RECT) print(f"putting RecordFront to {yes}") - ui_state.params.put_bool("RecordFront", yes) + ui_state.params.put_bool("RecordFront", yes, block=True) # Restart training? elif self._step == len(self._image_paths) - 1: @@ -156,7 +156,7 @@ class DeclinePage(Widget): click_callback=self._on_uninstall_clicked) def _on_uninstall_clicked(self): - ui_state.params.put_bool("DoUninstall", True) + ui_state.params.put_bool("DoUninstall", True, block=True) gui_app.request_close() def _render(self, _): @@ -209,8 +209,8 @@ class OnboardingWindow(Widget): self._state = OnboardingState.TERMS def _on_terms_accepted(self): - ui_state.params.put("HasAcceptedTerms", terms_version) - ui_state.params.put("HasAcceptedTermsSP", terms_version_sp) + ui_state.params.put("HasAcceptedTerms", terms_version, block=True) + ui_state.params.put("HasAcceptedTermsSP", terms_version_sp, block=True) if not self._sunnylink.completed: self._state = OnboardingState.SUNNYLINK_CONSENT elif not self._training_done: @@ -219,7 +219,7 @@ class OnboardingWindow(Widget): gui_app.pop_widget() def _on_completed_training(self): - ui_state.params.put("CompletedTrainingVersion", training_version) + ui_state.params.put("CompletedTrainingVersion", training_version, block=True) def _render(self, _): if self._training_guide is None: diff --git a/selfdrive/ui/layouts/settings/common.py b/selfdrive/ui/layouts/settings/common.py index 5e87a6447a..bba8606e64 100644 --- a/selfdrive/ui/layouts/settings/common.py +++ b/selfdrive/ui/layouts/settings/common.py @@ -1,5 +1,5 @@ from openpilot.selfdrive.ui.ui_state import ui_state -def restart_needed_callback(_): +def restart_needed_callback(_=None): ui_state.params.put_bool("OnroadCycleRequested", True) diff --git a/selfdrive/ui/layouts/settings/developer.py b/selfdrive/ui/layouts/settings/developer.py index 964d28bf9c..a9fbca768d 100644 --- a/selfdrive/ui/layouts/settings/developer.py +++ b/selfdrive/ui/layouts/settings/developer.py @@ -23,7 +23,7 @@ DESCRIPTIONS = { "other than your own. A comma employee will NEVER ask you to add their GitHub username." ), 'alpha_longitudinal': tr_noop( - "WARNING: sunnypilot longitudinal control is in alpha for this car and will disable Automatic Emergency Braking (AEB).

" + + "WARNING: sunnypilot longitudinal control is in alpha for this car and may disable Automatic Emergency Braking (AEB).

" + "On this car, sunnypilot defaults to the car's built-in ACC instead of sunnypilot's longitudinal control. " + "Enable this to switch to sunnypilot longitudinal control. " + "Enabling Experimental mode is recommended when enabling sunnypilot longitudinal control alpha. " + @@ -135,12 +135,6 @@ class DeveloperLayout(Widget): long_man_enabled = ui_state.has_longitudinal_control and ui_state.is_offroad() self._long_maneuver_toggle.action_item.set_enabled(long_man_enabled) - if not long_man_enabled: - self._long_maneuver_toggle.action_item.set_state(False) - self._params.put_bool("LongitudinalManeuverMode", False) - - lat_man_enabled = ui_state.is_offroad() - self._lat_maneuver_toggle.action_item.set_enabled(lat_man_enabled) else: self._long_maneuver_toggle.action_item.set_enabled(False) self._lat_maneuver_toggle.action_item.set_enabled(False) @@ -160,45 +154,45 @@ class DeveloperLayout(Widget): item.action_item.set_state(self._params.get_bool(key)) def _on_enable_ui_debug(self, state: bool): - self._params.put_bool("ShowDebugInfo", state) + self._params.put_bool("ShowDebugInfo", state, block=True) gui_app.set_show_touches(state) gui_app.set_show_fps(state) gui_app.set_show_mouse_coords(state) def _on_enable_adb(self, state: bool): - self._params.put_bool("AdbEnabled", state) + self._params.put_bool("AdbEnabled", state, block=True) def _on_enable_ssh(self, state: bool): - self._params.put_bool("SshEnabled", state) + self._params.put_bool("SshEnabled", state, block=True) def _on_joystick_debug_mode(self, state: bool): - self._params.put_bool("JoystickDebugMode", state) - self._params.put_bool("LongitudinalManeuverMode", False) + self._params.put_bool("JoystickDebugMode", state, block=True) + self._params.put_bool("LongitudinalManeuverMode", False, block=True) self._long_maneuver_toggle.action_item.set_state(False) - self._params.put_bool("LateralManeuverMode", False) + self._params.put_bool("LateralManeuverMode", False, block=True) self._lat_maneuver_toggle.action_item.set_state(False) def _on_long_maneuver_mode(self, state: bool): - self._params.put_bool("LongitudinalManeuverMode", state) - self._params.put_bool("JoystickDebugMode", False) + self._params.put_bool("LongitudinalManeuverMode", state, block=True) + self._params.put_bool("JoystickDebugMode", False, block=True) self._joystick_toggle.action_item.set_state(False) - self._params.put_bool("LateralManeuverMode", False) + self._params.put_bool("LateralManeuverMode", False, block=True) self._lat_maneuver_toggle.action_item.set_state(False) def _on_lat_maneuver_mode(self, state: bool): - self._params.put_bool("LateralManeuverMode", state) - self._params.put_bool("ExperimentalMode", False) - self._params.put_bool("JoystickDebugMode", False) + self._params.put_bool("LateralManeuverMode", state, block=True) + self._params.put_bool("ExperimentalMode", False, block=True) + self._params.put_bool("JoystickDebugMode", False, block=True) self._joystick_toggle.action_item.set_state(False) - self._params.put_bool("LongitudinalManeuverMode", False) + self._params.put_bool("LongitudinalManeuverMode", False, block=True) self._long_maneuver_toggle.action_item.set_state(False) def _on_alpha_long_enabled(self, state: bool): if state: def confirm_callback(result: DialogResult): if result == DialogResult.CONFIRM: - self._params.put_bool("AlphaLongitudinalEnabled", True) - self._params.put_bool("OnroadCycleRequested", True) + self._params.put_bool("AlphaLongitudinalEnabled", True, block=True) + self._params.put_bool("OnroadCycleRequested", True, block=True) self._update_toggles() else: self._alpha_long_toggle.action_item.set_state(False) @@ -211,6 +205,6 @@ class DeveloperLayout(Widget): gui_app.push_widget(dlg) else: - self._params.put_bool("AlphaLongitudinalEnabled", False) - self._params.put_bool("OnroadCycleRequested", True) + self._params.put_bool("AlphaLongitudinalEnabled", False, block=True) + self._params.put_bool("OnroadCycleRequested", True, block=True) self._update_toggles() diff --git a/selfdrive/ui/layouts/settings/device.py b/selfdrive/ui/layouts/settings/device.py index 126ad22a3a..2e0493c8d3 100644 --- a/selfdrive/ui/layouts/settings/device.py +++ b/selfdrive/ui/layouts/settings/device.py @@ -108,7 +108,7 @@ class DeviceLayout(Widget): self._params.remove("LiveParameters") self._params.remove("LiveParametersV2") self._params.remove("LiveDelay") - self._params.put_bool("OnroadCycleRequested", True) + self._params.put_bool("OnroadCycleRequested", True, block=True) self._update_calib_description() dialog = ConfirmDialog(tr("Are you sure you want to reset calibration?"), tr("Reset"), callback=reset_calibration) @@ -169,7 +169,7 @@ class DeviceLayout(Widget): def perform_reboot(result: DialogResult): if not ui_state.engaged and result == DialogResult.CONFIRM: - self._params.put_bool_nonblocking("DoReboot", True) + self._params.put_bool("DoReboot", True) dialog = ConfirmDialog(tr("Are you sure you want to reboot?"), tr("Reboot"), callback=perform_reboot) gui_app.push_widget(dialog) @@ -181,7 +181,7 @@ class DeviceLayout(Widget): def perform_power_off(result: DialogResult): if not ui_state.engaged and result == DialogResult.CONFIRM: - self._params.put_bool_nonblocking("DoShutdown", True) + self._params.put_bool("DoShutdown", True) dialog = ConfirmDialog(tr("Are you sure you want to power off?"), tr("Power Off"), callback=perform_power_off) gui_app.push_widget(dialog) diff --git a/selfdrive/ui/layouts/settings/firehose.py b/selfdrive/ui/layouts/settings/firehose.py index 18514feeb9..8ac6fe3d23 100644 --- a/selfdrive/ui/layouts/settings/firehose.py +++ b/selfdrive/ui/layouts/settings/firehose.py @@ -1,7 +1,7 @@ import pyray as rl from openpilot.system.ui.lib.application import gui_app, FontWeight, FONT_SCALE -from openpilot.system.ui.lib.multilang import tr, trn, tr_noop +from openpilot.system.ui.lib.multilang import tr, tr_noop from openpilot.system.ui.lib.text_measure import measure_text_cached from openpilot.system.ui.lib.scroll_panel import GuiScrollPanel from openpilot.system.ui.lib.wrap_text import wrap_text @@ -65,12 +65,13 @@ class FirehoseLayout(FirehoseLayoutBase): y = self._draw_wrapped_text(x, y, w, status_text, gui_app.font(FontWeight.BOLD), 60, status_color) y += 20 + 20 + # TODO: add back once reliable # Contribution count (if available) - if self._segment_count > 0: - contrib_text = trn("{} segment of your driving is in the training dataset so far.", - "{} segments of your driving is in the training dataset so far.", self._segment_count).format(self._segment_count) - y = self._draw_wrapped_text(x, y, w, contrib_text, gui_app.font(FontWeight.BOLD), 52, rl.WHITE) - y += 20 + 20 + #if self._segment_count > 0: + # contrib_text = trn("{} segment of your driving is in the training dataset so far.", + # "{} segments of your driving is in the training dataset so far.", self._segment_count).format(self._segment_count) + # y = self._draw_wrapped_text(x, y, w, contrib_text, gui_app.font(FontWeight.BOLD), 52, rl.WHITE) + # y += 20 + 20 # Separator rl.draw_rectangle(x, y, w, 2, self.GRAY) diff --git a/selfdrive/ui/layouts/settings/software.py b/selfdrive/ui/layouts/settings/software.py index f42682e2f7..4ed9f8fe19 100644 --- a/selfdrive/ui/layouts/settings/software.py +++ b/selfdrive/ui/layouts/settings/software.py @@ -170,7 +170,7 @@ class SoftwareLayout(Widget): def _on_uninstall(self): def handle_uninstall_confirmation(result: DialogResult): if result == DialogResult.CONFIRM: - ui_state.params.put_bool("DoUninstall", True) + ui_state.params.put_bool("DoUninstall", True, block=True) dialog = ConfirmDialog(tr("Are you sure you want to uninstall?"), tr("Uninstall"), callback=handle_uninstall_confirmation) gui_app.push_widget(dialog) @@ -178,7 +178,7 @@ class SoftwareLayout(Widget): def _on_install_update(self): # Trigger reboot to install update self._install_btn.action_item.set_enabled(False) - ui_state.params.put_bool("DoReboot", True) + ui_state.params.put_bool("DoReboot", True, block=True) def _on_select_branch(self): # Get available branches and order @@ -197,7 +197,7 @@ class SoftwareLayout(Widget): # Confirmed selection if result == DialogResult.CONFIRM and self._branch_dialog is not None and self._branch_dialog.selection: selection = self._branch_dialog.selection - ui_state.params.put("UpdaterTargetBranch", selection) + ui_state.params.put("UpdaterTargetBranch", selection, block=True) self._branch_btn.action_item.set_value(selection) os.system("pkill -SIGUSR1 -f system.updated.updated") self._branch_dialog = None diff --git a/selfdrive/ui/layouts/settings/toggles.py b/selfdrive/ui/layouts/settings/toggles.py index dfd0c73f61..4c83584ad5 100644 --- a/selfdrive/ui/layouts/settings/toggles.py +++ b/selfdrive/ui/layouts/settings/toggles.py @@ -221,8 +221,8 @@ class TogglesLayout(Widget): if state and not confirmed: def confirm_callback(result: DialogResult): if result == DialogResult.CONFIRM: - self._params.put_bool("ExperimentalMode", True) - self._params.put_bool("ExperimentalModeConfirmed", True) + self._params.put_bool("ExperimentalMode", True, block=True) + self._params.put_bool("ExperimentalModeConfirmed", True, block=True) else: self._toggles["ExperimentalMode"].action_item.set_state(False) self._update_experimental_mode_icon() @@ -234,16 +234,16 @@ class TogglesLayout(Widget): gui_app.push_widget(dlg) else: self._update_experimental_mode_icon() - self._params.put_bool("ExperimentalMode", state) + self._params.put_bool("ExperimentalMode", state, block=True) def _toggle_callback(self, state: bool, param: str): if param == "ExperimentalMode": self._handle_experimental_mode_toggle(state) return - self._params.put_bool(param, state) + self._params.put_bool(param, state, block=True) if self._toggle_defs[param][3]: - self._params.put_bool("OnroadCycleRequested", True) + self._params.put_bool("OnroadCycleRequested", True, block=True) def _set_longitudinal_personality(self, button_index: int): - self._params.put("LongitudinalPersonality", button_index) + self._params.put("LongitudinalPersonality", button_index, block=True) diff --git a/selfdrive/ui/layouts/sidebar.py b/selfdrive/ui/layouts/sidebar.py index 1dad597ca3..3405667245 100644 --- a/selfdrive/ui/layouts/sidebar.py +++ b/selfdrive/ui/layouts/sidebar.py @@ -125,10 +125,8 @@ class Sidebar(Widget, SidebarSP): def _update_temperature_status(self, device_state): thermal_status = device_state.thermalStatus - if thermal_status == ThermalStatus.green: + if thermal_status == ThermalStatus.ok: self._temp_status.update(tr_noop("TEMP"), tr_noop("GOOD"), Colors.GOOD) - elif thermal_status == ThermalStatus.yellow: - self._temp_status.update(tr_noop("TEMP"), tr_noop("OK"), Colors.WARNING) else: self._temp_status.update(tr_noop("TEMP"), tr_noop("HIGH"), Colors.DANGER) diff --git a/selfdrive/ui/lib/prime_state.py b/selfdrive/ui/lib/prime_state.py index 1aed949bee..b57380ac57 100644 --- a/selfdrive/ui/lib/prime_state.py +++ b/selfdrive/ui/lib/prime_state.py @@ -6,6 +6,7 @@ import time from openpilot.common.api import api_get from openpilot.common.params import Params +from openpilot.common.realtime import drop_realtime from openpilot.common.swaglog import cloudlog from openpilot.system.athena.registration import UNREGISTERED_DONGLE_ID from openpilot.selfdrive.ui.lib.api_helpers import get_token @@ -69,6 +70,7 @@ class PrimeState: cloudlog.info(f"Prime type updated to {prime_type}") def _worker_thread(self) -> None: + drop_realtime() from openpilot.selfdrive.ui.ui_state import ui_state, device while self._running: if not ui_state.started and device._awake: diff --git a/selfdrive/ui/mici/layouts/home.py b/selfdrive/ui/mici/layouts/home.py index cc424fa62b..d41165a79d 100644 --- a/selfdrive/ui/mici/layouts/home.py +++ b/selfdrive/ui/mici/layouts/home.py @@ -14,7 +14,6 @@ from openpilot.system.version import RELEASE_BRANCHES HEAD_BUTTON_FONT_SIZE = 40 HOME_PADDING = 8 -SETTINGS_ZONE_WIDTH = 280 ALERTS_ZONE_WIDTH = 180 NetworkType = log.DeviceState.NetworkType @@ -39,11 +38,16 @@ class AlertsPill(Widget): self.set_rect(rl.Rectangle(0, 0, 104, 52)) self._pill_bg_txt = gui_app.texture("icons_mici/alerts_pill.png", 104, 52) - self._warning_txt = gui_app.texture("icons_mici/offroad_alerts/red_warning.png", 36, 36) + self._icon_red = gui_app.texture("icons_mici/offroad_alerts/red_warning.png", 36, 36) + self._icon_orange = gui_app.texture("icons_mici/offroad_alerts/orange_warning.png", 36, 36) + self._icon_green = gui_app.texture("icons_mici/offroad_alerts/green_wheel.png", 36, 36) self._alert_count_callback: Callable[[], int] | None = None + self._max_severity_callback: Callable[[], int | None] | None = None - def set_alert_count_callback(self, callback: Callable[[], int] | None): + def set_alert_count_callback(self, callback: Callable[[], int] | None, + severity_callback: Callable[[], int | None] | None = None): self._alert_count_callback = callback + self._max_severity_callback = severity_callback def _render(self, _): alert_count = self._alert_count_callback() if self._alert_count_callback else 0 @@ -51,9 +55,17 @@ class AlertsPill(Widget): pill_w, pill_h = self._pill_bg_txt.width, self._pill_bg_txt.height rl.draw_texture_ex(self._pill_bg_txt, rl.Vector2(self.rect.x, self.rect.y), 0.0, 1.0, rl.WHITE) + severity = self._max_severity_callback() if self._max_severity_callback else None + if severity == -1: + warning_txt = self._icon_green + elif severity is not None and severity > 0: + warning_txt = self._icon_red + else: + warning_txt = self._icon_orange + warn_x = self.rect.x + self.ICON_OFFSET - warn_y = self.rect.y + (pill_h - self._warning_txt.height) / 2 - rl.draw_texture_ex(self._warning_txt, rl.Vector2(warn_x, warn_y), 0.0, 1.0, rl.WHITE) + warn_y = self.rect.y + (pill_h - warning_txt.height) / 2 + rl.draw_texture_ex(warning_txt, rl.Vector2(warn_x, warn_y), 0.0, 1.0, rl.WHITE) count_rect = rl.Rectangle(self.rect.x + self.COUNT_OFFSET, self.rect.y, pill_w - self.COUNT_OFFSET, pill_h) gui_label(count_rect, str(alert_count), font_size=36, @@ -120,16 +132,17 @@ class MiciHomeLayout(Widget): self._on_alerts_click: Callable | None = None self._alert_count_callback: Callable[[], int] | None = None - self._last_refresh = 0 self._mouse_down_t: None | float = None self._did_long_press = False self._is_pressed_prev = False - self._version_text = None - self._experimental_mode = False + self._version_text = self._get_version_text() self._experimental_icon = IconWidget("icons_mici/experimental_mode.png", (48, 48)) + self._egpu_icon = IconWidget("icons_mici/egpu.png", (50, 37)) + self._egpu_icon_gray = IconWidget("icons_mici/egpu_gray.png", (50, 37)) self._mic_icon = IconWidget("icons_mici/microphone.png", (32, 46)) + self._body_icon = IconWidget("icons_mici/body.png", (54, 37)) self._alerts_pill = AlertsPill() @@ -137,6 +150,9 @@ class MiciHomeLayout(Widget): IconWidget("icons_mici/settings.png", (48, 48), opacity=0.9), NetworkIcon(), self._experimental_icon, + self._egpu_icon, + self._egpu_icon_gray, + self._body_icon, self._mic_icon, ], spacing=18) @@ -147,14 +163,6 @@ class MiciHomeLayout(Widget): self._branch_label = UnifiedLabel("", font_size=36, text_color=rl.GRAY, font_weight=FontWeight.ROMAN, scroll=True) self._version_commit_label = UnifiedLabel("", font_size=36, text_color=rl.GRAY, font_weight=FontWeight.ROMAN, max_width=480, wrap_text=False) - def show_event(self): - super().show_event() - self._version_text = self._get_version_text() - self._update_params() - - def _update_params(self): - self._experimental_mode = ui_state.params.get_bool("ExperimentalMode") - def _update_state(self): if self.is_pressed and not self._is_pressed_prev: self._mouse_down_t = time.monotonic() @@ -167,34 +175,28 @@ class MiciHomeLayout(Widget): if time.monotonic() - self._mouse_down_t > 0.5: # long gating for experimental mode - only allow toggle if longitudinal control is available if ui_state.has_longitudinal_control: - self._experimental_mode = not self._experimental_mode - ui_state.params.put("ExperimentalMode", self._experimental_mode) + ui_state.experimental_mode = not ui_state.experimental_mode + ui_state.params.put("ExperimentalMode", ui_state.experimental_mode, block=True) self._mouse_down_t = None self._did_long_press = True - if rl.get_time() - self._last_refresh > 5.0: - # Update version text - self._version_text = self._get_version_text() - self._last_refresh = rl.get_time() - self._update_params() - def set_callbacks(self, on_settings: Callable | None = None, on_alerts: Callable | None = None, - alert_count_callback: Callable[[], int] | None = None): + alert_count_callback: Callable[[], int] | None = None, + max_severity_callback: Callable[[], int | None] | None = None): self._on_settings_click = on_settings self._on_alerts_click = on_alerts self._alert_count_callback = alert_count_callback - self._alerts_pill.set_alert_count_callback(alert_count_callback) + self._alerts_pill.set_alert_count_callback(alert_count_callback, max_severity_callback) def _handle_mouse_release(self, mouse_pos: MousePos): if not self._did_long_press: relative_x = mouse_pos.x - self.rect.x has_alerts = self._alert_count_callback and self._alert_count_callback() > 0 - if relative_x < SETTINGS_ZONE_WIDTH: - if self._on_settings_click: - self._on_settings_click() - elif has_alerts and relative_x > self.rect.width - ALERTS_ZONE_WIDTH: + if has_alerts and relative_x > self.rect.width - ALERTS_ZONE_WIDTH: if self._on_alerts_click: self._on_alerts_click() + elif self._on_settings_click: + self._on_settings_click() self._did_long_press = False def _get_version_text(self) -> tuple[str, str, str, str] | None: @@ -245,8 +247,11 @@ class MiciHomeLayout(Widget): self._version_commit_label.render() # ***** Center-aligned bottom section icons ***** - self._experimental_icon.set_visible(self._experimental_mode) + self._experimental_icon.set_visible(ui_state.experimental_mode) + self._egpu_icon.set_visible(ui_state.usbgpu and ui_state.usbgpu_compiled) + self._egpu_icon_gray.set_visible(ui_state.usbgpu and not ui_state.usbgpu_compiled) self._mic_icon.set_visible(ui_state.recording_audio) + self._body_icon.set_visible(ui_state.is_body) footer_rect = rl.Rectangle(self.rect.x + HOME_PADDING, self.rect.y + self.rect.height - 48, self.rect.width - HOME_PADDING, 48) self._status_bar_layout.render(footer_rect) diff --git a/selfdrive/ui/mici/layouts/main.py b/selfdrive/ui/mici/layouts/main.py index 0c762e098d..e25b2840f7 100644 --- a/selfdrive/ui/mici/layouts/main.py +++ b/selfdrive/ui/mici/layouts/main.py @@ -6,6 +6,7 @@ from openpilot.selfdrive.ui.mici.layouts.offroad_alerts import MiciOffroadAlerts from openpilot.selfdrive.ui.mici.onroad.augmented_road_view import AugmentedRoadView from openpilot.selfdrive.ui.ui_state import device, ui_state from openpilot.selfdrive.ui.mici.layouts.onboarding import OnboardingWindow +from openpilot.selfdrive.ui.body.layouts.onroad import BodyLayout from openpilot.system.ui.widgets import Widget from openpilot.system.ui.widgets.scroller import Scroller from openpilot.system.ui.lib.application import gui_app @@ -31,22 +32,25 @@ class MiciMainLayout(Scroller): self._home_layout = MiciHomeLayout() self._alerts_layout = MiciOffroadAlerts() self._settings_layout = SettingsLayout() - self._onroad_layout = AugmentedRoadView(bookmark_callback=self._on_bookmark_clicked) + self._car_onroad_layout = AugmentedRoadView(bookmark_callback=self._on_bookmark_clicked) + self._body_onroad_layout = BodyLayout() # Initialize widget rects - for widget in (self._home_layout, self._settings_layout, self._alerts_layout, self._onroad_layout): + for widget in (self._home_layout, self._alerts_layout, self._settings_layout, + self._car_onroad_layout, self._body_onroad_layout): # TODO: set parent rect and use it if never passed rect from render (like in Scroller) widget.set_rect(rl.Rectangle(0, 0, gui_app.width, gui_app.height)) self._scroller.add_widgets([ self._alerts_layout, self._home_layout, - self._onroad_layout, + self._car_onroad_layout, + self._body_onroad_layout, ]) self._scroller.set_reset_scroll_at_show(False) # Disable scrolling when onroad is interacting with bookmark - self._scroller.set_scrolling_enabled(lambda: not self._onroad_layout.is_swiping_left()) + self._scroller.set_scrolling_enabled(lambda: not self._car_onroad_layout.is_swiping_left()) # Set callbacks self._setup_callbacks() @@ -59,14 +63,23 @@ class MiciMainLayout(Scroller): if not self._onboarding_window.completed: gui_app.push_widget(self._onboarding_window) + @property + def _onroad_layout(self) -> Widget: + # For scroll_to + return self._body_onroad_layout if ui_state.is_body else self._car_onroad_layout + def _setup_callbacks(self): self._home_layout.set_callbacks( on_settings=lambda: gui_app.push_widget(self._settings_layout), on_alerts=lambda: self._scroll_to(self._alerts_layout), alert_count_callback=self._alerts_layout.active_alerts, + max_severity_callback=self._alerts_layout.max_severity, ) - self._onroad_layout.set_click_callback(lambda: self._scroll_to(self._home_layout)) + for layout in (self._car_onroad_layout, self._body_onroad_layout): + layout.set_click_callback(lambda: self._scroll_to(self._home_layout)) + device.add_interactive_timeout_callback(self._on_interactive_timeout) + ui_state.add_on_body_changed_callbacks(self._on_body_changed) def _scroll_to(self, layout: Widget): layout_x = int(layout.rect.x) @@ -132,3 +145,7 @@ class MiciMainLayout(Scroller): user_bookmark = messaging.new_message('bookmarkButton') user_bookmark.valid = True self._pm.send('bookmarkButton', user_bookmark) + + def _on_body_changed(self): + self._car_onroad_layout.set_visible(not ui_state.is_body) + self._body_onroad_layout.set_visible(ui_state.is_body) diff --git a/selfdrive/ui/mici/layouts/offroad_alerts.py b/selfdrive/ui/mici/layouts/offroad_alerts.py index 57ddfdbc48..e0c574dc07 100644 --- a/selfdrive/ui/mici/layouts/offroad_alerts.py +++ b/selfdrive/ui/mici/layouts/offroad_alerts.py @@ -1,9 +1,11 @@ import pyray as rl import re +import threading import time from dataclasses import dataclass from enum import IntEnum from openpilot.common.params import Params +from openpilot.common.realtime import drop_realtime from openpilot.selfdrive.selfdrived.alertmanager import OFFROAD_ALERTS from openpilot.system.hardware import HARDWARE from openpilot.system.ui.widgets import Widget @@ -195,7 +197,6 @@ class MiciOffroadAlerts(Scroller): self.params = Params() self.sorted_alerts: list[AlertData] = [] self.alert_items: list[AlertItem] = [] - self._last_refresh = 0.0 # Create empty state label self._empty_label = UnifiedLabel(tr("no alerts"), 65, FontWeight.DISPLAY, rl.WHITE, @@ -205,9 +206,17 @@ class MiciOffroadAlerts(Scroller): # Build initial alert list self._build_alerts() + # Start param thread + self._pending_params: dict | None = None + self._params_thread = threading.Thread(target=self._params_worker, daemon=True) + self._params_thread.start() + def active_alerts(self) -> int: return sum(alert.visible for alert in self.sorted_alerts) + def max_severity(self) -> int | None: + return max((alert.severity for alert in self.sorted_alerts if alert.visible), default=None) + def scrolling(self): return self._scroller.scroll_panel.is_touch_valid() @@ -234,12 +243,19 @@ class MiciOffroadAlerts(Scroller): self.alert_items.append(alert_item) self._scroller.add_widget(alert_item) - def refresh(self) -> int: + def _params_worker(self): + drop_realtime() + while True: + self._pending_params = ({"UpdaterNewDescription": self.params.get("UpdaterNewDescription")} | + {alert_data.key: self.params.get(alert_data.key) for alert_data in self.sorted_alerts}) + time.sleep(REFRESH_INTERVAL) + + def _refresh(self) -> int: """Refresh alerts from params and return active count.""" active_count = 0 # Handle UpdateAvailable alert specially - update_available = self.params.get_bool("UpdateAvailable") + update_available = self._pending_params["UpdateAvailable"] update_alert_data = next((alert_data for alert_data in self.sorted_alerts if alert_data.key == "UpdateAvailable"), None) if update_alert_data: @@ -247,7 +263,7 @@ class MiciOffroadAlerts(Scroller): version_string = "" # Get new version description and parse version and date - new_desc = self.params.get("UpdaterNewDescription") or "" + new_desc = self._pending_params["UpdaterNewDescription"] or "" if new_desc: # format: "version / branch / commit / date" parts = new_desc.split(" / ") @@ -268,11 +284,16 @@ class MiciOffroadAlerts(Scroller): continue # Skip, already handled above text = "" - alert_json = self.params.get(alert_data.key) + alert_json = self._pending_params[alert_data.key] if alert_json: text = alert_json.get("text", "").replace("%1", alert_json.get("extra", "")) + if text and not alert_data.visible: + # Bump newly visible alerts to the top, severity sort keeps it at the top of its category + widget = next(w for w in self._scroller.items if w.alert_data is alert_data) + self._scroller.items.remove(widget) + self._scroller.items.insert(0, widget) alert_data.text = text alert_data.visible = bool(text) @@ -283,21 +304,16 @@ class MiciOffroadAlerts(Scroller): for alert_item in self.alert_items: alert_item.update_alert_data(alert_item.alert_data) - return active_count + self._scroller.items.sort(key=lambda w: -w.alert_data.severity) - def show_event(self): - """Reset scroll position when shown and refresh alerts.""" - super().show_event() - self._last_refresh = time.monotonic() - self.refresh() + return active_count def _update_state(self): """Periodically refresh alerts.""" - # Refresh alerts periodically, not every frame - current_time = time.monotonic() - if current_time - self._last_refresh >= REFRESH_INTERVAL: - self.refresh() - self._last_refresh = current_time + # Refresh alerts when thread updates params + if self._pending_params is not None: + self._refresh() + self._pending_params = None def _render(self, rect: rl.Rectangle): """Render the alerts scroller or empty state.""" diff --git a/selfdrive/ui/mici/layouts/onboarding.py b/selfdrive/ui/mici/layouts/onboarding.py index d6d3f70330..f070ec5d5c 100644 --- a/selfdrive/ui/mici/layouts/onboarding.py +++ b/selfdrive/ui/mici/layouts/onboarding.py @@ -71,7 +71,7 @@ class TrainingGuidePreDMTutorial(NavScroller): def show_event(self): super().show_event() # Get driver monitoring model ready for next step - ui_state.params.put_bool_nonblocking("IsDriverViewEnabled", True) + ui_state.params.put_bool("IsDriverViewEnabled", True) class DMBadFaceDetected(NavScroller): @@ -123,7 +123,7 @@ class TrainingGuideDMTutorial(NavWidget): def _update_state(self): super()._update_state() if device.awake and not ui_state.params.get_bool("IsDriverViewEnabled"): - ui_state.params.put_bool_nonblocking("IsDriverViewEnabled", True) + ui_state.params.put_bool("IsDriverViewEnabled", True) sm = ui_state.sm if sm.recv_frame.get("driverMonitoringState", 0) == 0: @@ -140,7 +140,7 @@ class TrainingGuideDMTutorial(NavWidget): # stay at 100% once reached in_bad_face = gui_app.get_active_widget() == self._bad_face_page - if ((dm_state.faceDetected and looking_center) or self._progress.x > 0.99) and not in_bad_face: + if ((dm_state.visionPolicyState.faceDetected and looking_center) or self._progress.x > 0.99) and not in_bad_face: slow = self._progress.x < 0.25 duration = self.PROGRESS_DURATION * 2 if slow else self.PROGRESS_DURATION self._progress.x += 1.0 / (duration * gui_app.target_fps) @@ -219,11 +219,11 @@ class TrainingGuideRecordFront(NavScroller): super().__init__() def on_accept(): - ui_state.params.put_bool_nonblocking("RecordFront", True) + ui_state.params.put_bool("RecordFront", True) continue_callback() def on_decline(): - ui_state.params.put_bool_nonblocking("RecordFront", False) + ui_state.params.put_bool("RecordFront", False) continue_callback() self._accept_button = BigConfirmationCircleButton("allow data uploading", gui_app.texture("icons_mici/setup/driver_monitoring/dm_check.png", 64, 64), @@ -367,7 +367,7 @@ class OnboardingWindow(Widget): self._needs_initial_push = False def _on_uninstall(self): - ui_state.params.put_bool("DoUninstall", True) + ui_state.params.put_bool("DoUninstall", True, block=True) def show_event(self): super().show_event() @@ -386,12 +386,12 @@ class OnboardingWindow(Widget): return self._accepted_terms and self._sunnylink_consent_done and self._training_done def close(self): - ui_state.params.put_bool_nonblocking("IsDriverViewEnabled", False) + ui_state.params.put_bool("IsDriverViewEnabled", False) self._completed_callback() def _on_terms_accepted(self): - ui_state.params.put("HasAcceptedTerms", terms_version) - ui_state.params.put("HasAcceptedTermsSP", terms_version_sp) + ui_state.params.put("HasAcceptedTerms", terms_version, block=True) + ui_state.params.put("HasAcceptedTermsSP", terms_version_sp, block=True) self._accepted_terms = True if not self._sunnylink_consent_done: gui_app.push_widget(self._sunnylink_consent) @@ -401,7 +401,7 @@ class OnboardingWindow(Widget): self.close() def _on_sunnylink_accepted(self): - ui_state.params.put("CompletedSunnylinkConsentVersion", sunnylink_consent_version) + ui_state.params.put("CompletedSunnylinkConsentVersion", sunnylink_consent_version, block=True) ui_state.params.put_bool("SunnylinkEnabled", True) self._sunnylink_consent_done = True if not self._training_done: @@ -410,7 +410,7 @@ class OnboardingWindow(Widget): self.close() def _on_sunnylink_declined(self): - ui_state.params.put("CompletedSunnylinkConsentVersion", sunnylink_consent_declined) + ui_state.params.put("CompletedSunnylinkConsentVersion", sunnylink_consent_declined, block=True) ui_state.params.put_bool("SunnylinkEnabled", False) self._sunnylink_consent_done = True if not self._training_done: @@ -419,7 +419,7 @@ class OnboardingWindow(Widget): self.close() def _on_completed_training(self): - ui_state.params.put("CompletedTrainingVersion", training_version) + ui_state.params.put("CompletedTrainingVersion", training_version, block=True) self._training_done = True self.close() diff --git a/selfdrive/ui/mici/layouts/settings/developer.py b/selfdrive/ui/mici/layouts/settings/developer.py index f47614c073..2f0250ff5f 100644 --- a/selfdrive/ui/mici/layouts/settings/developer.py +++ b/selfdrive/ui/mici/layouts/settings/developer.py @@ -1,13 +1,34 @@ +from collections.abc import Callable from openpilot.common.time_helpers import system_time_valid from openpilot.system.ui.widgets.scroller import NavScroller -from openpilot.selfdrive.ui.mici.widgets.button import BigButton, BigToggle, BigParamControl, BigCircleParamControl -from openpilot.selfdrive.ui.mici.widgets.dialog import BigDialog, BigInputDialog +from openpilot.selfdrive.ui.mici.widgets.button import BigButton, BigToggle, BigParamControl, BigCircleParamControl, GreyBigButton +from openpilot.selfdrive.ui.mici.widgets.dialog import BigDialog, BigInputDialog, BigConfirmationCircleButton from openpilot.system.ui.lib.application import gui_app from openpilot.selfdrive.ui.layouts.settings.common import restart_needed_callback from openpilot.selfdrive.ui.ui_state import ui_state from openpilot.selfdrive.ui.widgets.ssh_key import SshKeyFetcher +class AlphaLongConfirmPage(NavScroller): + def __init__(self, on_confirm: Callable[[], None]): + super().__init__() + + accept = BigConfirmationCircleButton("enable alpha\nlongitudinal", + gui_app.texture("icons_mici/setup/driver_monitoring/dm_check.png", 64, 64), + lambda: self.dismiss(on_confirm)) + + self._scroller.add_widgets([ + GreyBigButton("enabling alpha longitudinal", "scroll to continue", + gui_app.texture("icons_mici/setup/warning.png", 64, 64)), + GreyBigButton("", "WARNING: alpha longitudinal control may disable Automatic Emergency Braking (AEB)"), + GreyBigButton("", "On this car, openpilot defaults to the stock system's built-in ACC."), + GreyBigButton("", "Enabling this will switch to openpilot longitudinal control."), + GreyBigButton("", "Using Experimental mode is recommended with openpilot longitudinal control alpha."), + GreyBigButton("", "Changing this setting will restart openpilot if the car is powered on."), + accept, + ]) + + class DeveloperLayoutMici(NavScroller): def __init__(self): super().__init__() @@ -131,12 +152,6 @@ class DeveloperLayoutMici(NavScroller): long_man_enabled = ui_state.has_longitudinal_control and ui_state.is_offroad() self._long_maneuver_toggle.set_enabled(long_man_enabled) - if not long_man_enabled: - self._long_maneuver_toggle.set_checked(False) - ui_state.params.put_bool("LongitudinalManeuverMode", False) - - lat_man_enabled = ui_state.is_offroad() - self._lat_maneuver_toggle.set_enabled(lat_man_enabled) else: self._long_maneuver_toggle.set_enabled(False) self._lat_maneuver_toggle.set_enabled(False) @@ -147,31 +162,38 @@ class DeveloperLayoutMici(NavScroller): item.set_checked(ui_state.params.get_bool(key)) def _on_joystick_debug_mode(self, state: bool): - ui_state.params.put_bool("JoystickDebugMode", state) - ui_state.params.put_bool("LongitudinalManeuverMode", False) + ui_state.params.put_bool("JoystickDebugMode", state, block=True) + ui_state.params.put_bool("LongitudinalManeuverMode", False, block=True) self._long_maneuver_toggle.set_checked(False) - ui_state.params.put_bool("LateralManeuverMode", False) + ui_state.params.put_bool("LateralManeuverMode", False, block=True) self._lat_maneuver_toggle.set_checked(False) def _on_long_maneuver_mode(self, state: bool): - ui_state.params.put_bool("LongitudinalManeuverMode", state) - ui_state.params.put_bool("JoystickDebugMode", False) + ui_state.params.put_bool("LongitudinalManeuverMode", state, block=True) + ui_state.params.put_bool("JoystickDebugMode", False, block=True) self._joystick_toggle.set_checked(False) - ui_state.params.put_bool("LateralManeuverMode", False) + ui_state.params.put_bool("LateralManeuverMode", False, block=True) self._lat_maneuver_toggle.set_checked(False) - restart_needed_callback(state) + restart_needed_callback() def _on_lat_maneuver_mode(self, state: bool): - ui_state.params.put_bool("LateralManeuverMode", state) - ui_state.params.put_bool("ExperimentalMode", False) - ui_state.params.put_bool("JoystickDebugMode", False) + ui_state.params.put_bool("LateralManeuverMode", state, block=True) + ui_state.params.put_bool("ExperimentalMode", False, block=True) + ui_state.params.put_bool("JoystickDebugMode", False, block=True) self._joystick_toggle.set_checked(False) - ui_state.params.put_bool("LongitudinalManeuverMode", False) + ui_state.params.put_bool("LongitudinalManeuverMode", False, block=True) self._long_maneuver_toggle.set_checked(False) - restart_needed_callback(state) + restart_needed_callback() def _on_alpha_long_enabled(self, state: bool): - # TODO: show confirmation dialog before enabling - ui_state.params.put_bool("AlphaLongitudinalEnabled", state) - restart_needed_callback(state) - self._update_toggles() + def do_toggle(_state: bool): + ui_state.params.put_bool("AlphaLongitudinalEnabled", _state, block=True) + restart_needed_callback() + self._update_toggles() + + if state: + # Don't show enabled state until confirm + self._alpha_long_toggle.set_checked(False) + gui_app.push_widget(AlphaLongConfirmPage(lambda: do_toggle(True))) + else: + do_toggle(False) diff --git a/selfdrive/ui/mici/layouts/settings/device.py b/selfdrive/ui/mici/layouts/settings/device.py index e0d89a5419..4a8fc50d53 100644 --- a/selfdrive/ui/mici/layouts/settings/device.py +++ b/selfdrive/ui/mici/layouts/settings/device.py @@ -40,7 +40,7 @@ class ReviewTrainingGuide(TrainingGuide): def hide_event(self): super().hide_event() device.set_override_interactive_timeout(None) - ui_state.params.put_bool_nonblocking("IsDriverViewEnabled", False) + ui_state.params.put_bool("IsDriverViewEnabled", False) class MiciFccModal(NavRawScrollPanel): @@ -200,7 +200,7 @@ class UpdateOpenpilotBigButton(BigButton): if self.get_value() == "download update": os.system("pkill -SIGHUP -f system.updated.updated") elif self.get_value() == "update now": - ui_state.params.put_bool("DoReboot", True) + ui_state.params.put_bool("DoReboot", True, block=True) else: os.system("pkill -SIGUSR1 -f system.updated.updated") @@ -258,6 +258,7 @@ class UpdateOpenpilotBigButton(BigButton): elif self._state == UpdaterState.IDLE: self.set_rotate_icon(False) if failed: + self.set_enabled(True) # allow retry when failure came from updater param if self.get_value() != "failed to update": self.set_value("failed to update") @@ -292,10 +293,10 @@ class DeviceLayoutMici(NavScroller): self._fcc_dialog: HtmlModal | None = None def power_off_callback(): - ui_state.params.put_bool("DoShutdown", True) + ui_state.params.put_bool("DoShutdown", True, block=True) def reboot_callback(): - ui_state.params.put_bool("DoReboot", True) + ui_state.params.put_bool("DoReboot", True, block=True) def reset_calibration_callback(): params = ui_state.params @@ -304,10 +305,10 @@ class DeviceLayoutMici(NavScroller): params.remove("LiveParameters") params.remove("LiveParametersV2") params.remove("LiveDelay") - params.put_bool("OnroadCycleRequested", True) + params.put_bool("OnroadCycleRequested", True, block=True) def uninstall_openpilot_callback(): - ui_state.params.put_bool("DoUninstall", True) + ui_state.params.put_bool("DoUninstall", True, block=True) reset_calibration_btn = EngagedConfirmationButton("reset calibration", "reset", gui_app.texture("icons_mici/settings/device/lkas.png", 122, 64), reset_calibration_callback) diff --git a/selfdrive/ui/mici/layouts/settings/firehose.py b/selfdrive/ui/mici/layouts/settings/firehose.py index 5bf7426c77..5e3b6da2cc 100644 --- a/selfdrive/ui/mici/layouts/settings/firehose.py +++ b/selfdrive/ui/mici/layouts/settings/firehose.py @@ -5,6 +5,7 @@ import pyray as rl from openpilot.common.api import api_get from openpilot.common.params import Params +from openpilot.common.realtime import drop_realtime from openpilot.common.swaglog import cloudlog from openpilot.selfdrive.ui.lib.api_helpers import get_token from openpilot.selfdrive.ui.ui_state import ui_state, device @@ -212,6 +213,7 @@ class FirehoseLayoutBase(Widget): cloudlog.error(f"Failed to fetch firehose stats: {e}") def _update_loop(self): + drop_realtime() while self._running: if not ui_state.started and device._awake: self._fetch_firehose_stats() diff --git a/selfdrive/ui/mici/layouts/settings/network/network_layout.py b/selfdrive/ui/mici/layouts/settings/network/network_layout.py index 9f6fae4b5f..58b3d0c77d 100644 --- a/selfdrive/ui/mici/layouts/settings/network/network_layout.py +++ b/selfdrive/ui/mici/layouts/settings/network/network_layout.py @@ -66,14 +66,14 @@ class NetworkLayoutMici(NavScroller): # ******** Advanced settings ******** # ******** Roaming toggle ******** - self._roaming_btn = BigParamControl("enable roaming", "GsmRoaming", toggle_callback=self._toggle_roaming) + self._roaming_btn = BigParamControl("enable roaming", "GsmRoaming") # ******** APN settings ******** self._apn_btn = BigButton("apn settings", "edit") self._apn_btn.set_click_callback(self._edit_apn) # ******** Cellular metered toggle ******** - self._cellular_metered_btn = BigParamControl("cellular metered", "GsmMetered", toggle_callback=self._toggle_cellular_metered) + self._cellular_metered_btn = BigParamControl("cellular metered", "GsmMetered") # Main scroller ---------------------------------- self._scroller.add_widgets([ @@ -88,11 +88,6 @@ class NetworkLayoutMici(NavScroller): # */ ]) - # Set initial config - roaming_enabled = ui_state.params.get_bool("GsmRoaming") - metered = ui_state.params.get_bool("GsmMetered") - self._wifi_manager.update_gsm_settings(roaming_enabled, ui_state.params.get("GsmApn") or "", metered) - def _update_state(self): super()._update_state() @@ -116,9 +111,6 @@ class NetworkLayoutMici(NavScroller): gui_app.remove_nav_stack_tick(self._wifi_manager.process_callbacks) - def _toggle_roaming(self, checked: bool): - self._wifi_manager.update_gsm_settings(checked, ui_state.params.get("GsmApn") or "", ui_state.params.get_bool("GsmMetered")) - def _edit_apn(self): def update_apn(apn: str): apn = apn.strip() @@ -127,15 +119,10 @@ class NetworkLayoutMici(NavScroller): else: ui_state.params.put("GsmApn", apn) - self._wifi_manager.update_gsm_settings(ui_state.params.get_bool("GsmRoaming"), apn, ui_state.params.get_bool("GsmMetered")) - current_apn = ui_state.params.get("GsmApn") or "" dlg = BigInputDialog("enter APN...", current_apn, minimum_length=0, confirm_callback=update_apn) gui_app.push_widget(dlg) - def _toggle_cellular_metered(self, checked: bool): - self._wifi_manager.update_gsm_settings(ui_state.params.get_bool("GsmRoaming"), ui_state.params.get("GsmApn") or "", checked) - def _on_network_updated(self, networks: list[Network]): # Update tethering state tethering_active = self._wifi_manager.is_tethering_active() diff --git a/selfdrive/ui/mici/layouts/settings/network/wifi_ui.py b/selfdrive/ui/mici/layouts/settings/network/wifi_ui.py index 006027e258..8404faf9f7 100644 --- a/selfdrive/ui/mici/layouts/settings/network/wifi_ui.py +++ b/selfdrive/ui/mici/layouts/settings/network/wifi_ui.py @@ -383,7 +383,7 @@ class WifiUIMici(NavScroller): if scroll: # Scroll to the new position of the network - self._scroller.scroll_to(self._scroller.scroll_panel.get_offset(), smooth=True) + self._scroller.scroll_to(self._scroller.scroll_panel.get_offset(), smooth=True, block_widget_interaction=True) def _update_state(self): super()._update_state() diff --git a/selfdrive/ui/mici/onroad/augmented_road_view.py b/selfdrive/ui/mici/onroad/augmented_road_view.py index 9910c955ec..8dafc4df57 100644 --- a/selfdrive/ui/mici/onroad/augmented_road_view.py +++ b/selfdrive/ui/mici/onroad/augmented_road_view.py @@ -1,7 +1,6 @@ -import time import numpy as np import pyray as rl -from cereal import messaging, car, log +from cereal import car, log from msgq.visionipc import VisionStreamType from openpilot.selfdrive.ui.ui_state import ui_state, UIStatus from openpilot.selfdrive.ui.mici.onroad import SIDE_PANEL_WIDTH @@ -143,9 +142,7 @@ class AugmentedRoadView(CameraView): self.view_from_calib = view_frame_from_device_frame.copy() self.view_from_wide_calib = view_frame_from_device_frame.copy() - self._last_calib_time: float = 0 - self._last_rect_dims = (0.0, 0.0) - self._last_stream_type = stream_type + self._matrix_cache_key: tuple | None = None self._cached_matrix: np.ndarray | None = None self._content_rect = rl.Rectangle() self._last_click_time = 0.0 @@ -165,9 +162,6 @@ class AugmentedRoadView(CameraView): self._fade_texture = gui_app.texture("icons_mici/onroad/onroad_fade.png") - # debug - self._pm = messaging.PubMaster(['uiDebug']) - def is_swiping_left(self) -> bool: """Check if currently swiping left (for scroller to disable).""" return self._bookmark_icon.is_swiping_left() @@ -189,7 +183,12 @@ class AugmentedRoadView(CameraView): super()._handle_mouse_release(mouse_pos) def _render(self, _): - start_draw = time.monotonic() + # Draw text if not onroad + if not ui_state.started: + rl.draw_rectangle_rec(self.rect, rl.BLACK) + self._offroad_label.render(self._rect) + return + self._switch_stream_if_needed(ui_state.sm) # Update calibration before rendering @@ -224,7 +223,7 @@ class AugmentedRoadView(CameraView): alert_to_render, not_animating_out = self._alert_renderer.will_render() # Hide DMoji when disengaged unless AlwaysOnDM is enabled - should_draw_dmoji = (not self._hud_renderer.drawing_top_icons() and ui_state.is_onroad() and + should_draw_dmoji = (not self._hud_renderer.drawing_top_icons() and (ui_state.status != UIStatus.DISENGAGED or ui_state.always_on_dm)) self._driver_state_renderer.set_should_draw(should_draw_dmoji) self._driver_state_renderer.set_position(self._rect.x + 16, self._rect.y + 10) @@ -233,9 +232,7 @@ class AugmentedRoadView(CameraView): self._hud_renderer.set_can_draw_top_icons(alert_to_render is None) self._hud_renderer.set_wheel_critical_icon(alert_to_render is not None and not not_animating_out and alert_to_render.visual_alert == car.CarControl.HUDControl.VisualAlert.steerRequired) - # TODO: have alert renderer draw offroad mici label below - if ui_state.started: - self._alert_renderer.render(self._content_rect) + self._alert_renderer.render(self._content_rect) self._hud_renderer.render(self._content_rect) # Draw fake rounded border @@ -250,16 +247,6 @@ class AugmentedRoadView(CameraView): self._bookmark_icon.render(self.rect) - # Draw darkened background and text if not onroad - if not ui_state.started: - rl.draw_rectangle(int(self.rect.x), int(self.rect.y), int(self.rect.width), int(self.rect.height), rl.Color(0, 0, 0, 175)) - self._offroad_label.render(self._rect) - - # publish uiDebug - msg = messaging.new_message('uiDebug') - msg.uiDebug.drawTimeMillis = (time.monotonic() - start_draw) * 1000 - self._pm.send('uiDebug', msg) - def _switch_stream_if_needed(self, sm): if sm['selfdriveState'].experimentalMode and WIDE_CAM in self.available_streams: v_ego = sm['carState'].vEgo @@ -300,10 +287,18 @@ class AugmentedRoadView(CameraView): self.view_from_wide_calib = view_frame_from_device_frame @ wide_from_device @ device_from_calib def _calc_frame_matrix(self, rect: rl.Rectangle) -> np.ndarray: + cache_key = ( + ui_state.sm.recv_frame['liveCalibration'], + int(self._content_rect.width), + int(self._content_rect.height), + self.stream_type, + round(ui_state.sm['carState'].vEgo, 1), + ) + + if cache_key == self._matrix_cache_key and self._cached_matrix is not None: + return self._cached_matrix + # Get camera configuration - # TODO: cache with vEgo? - calib_time = ui_state.sm.recv_frame['liveCalibration'] - current_dims = (self._content_rect.width, self._content_rect.height) device_camera = self.device_camera or DEFAULT_DEVICE_CAMERA is_wide_camera = self.stream_type == WIDE_CAM intrinsic = device_camera.ecam.intrinsics if is_wide_camera else device_camera.fcam.intrinsics @@ -319,7 +314,6 @@ class AugmentedRoadView(CameraView): kep = calib_transform @ inf_point # Calculate center points and dimensions - x, y = self._content_rect.x, self._content_rect.y w, h = self._content_rect.width, self._content_rect.height cx, cy = intrinsic[0, 2], intrinsic[1, 2] @@ -339,18 +333,17 @@ class AugmentedRoadView(CameraView): x_offset, y_offset = 0, 0 # Cache the computed transformation matrix to avoid recalculations - self._last_calib_time = calib_time - self._last_rect_dims = current_dims - self._last_stream_type = self.stream_type + self._matrix_cache_key = cache_key self._cached_matrix = np.array([ [zoom * 2 * cx / w, 0, -x_offset / w * 2], [0, zoom * 2 * cy / h, -y_offset / h * 2], [0, 0, 1.0] ]) + # built without rect.x/y so cache stays hot during scroll. ModelRenderer adds offset at draw time video_transform = np.array([ - [zoom, 0.0, (w / 2 + x - x_offset) - (cx * zoom)], - [0.0, zoom, (h / 2 + y - y_offset) - (cy * zoom)], + [zoom, 0.0, (w / 2 - x_offset) - (cx * zoom)], + [0.0, zoom, (h / 2 - y_offset) - (cy * zoom)], [0.0, 0.0, 1.0] ]) self._model_renderer.set_transform(video_transform @ calib_transform) diff --git a/selfdrive/ui/mici/onroad/cameraview.py b/selfdrive/ui/mici/onroad/cameraview.py index 62fcfd0654..86dd95f466 100644 --- a/selfdrive/ui/mici/onroad/cameraview.py +++ b/selfdrive/ui/mici/onroad/cameraview.py @@ -150,15 +150,11 @@ class CameraView(Widget): ui_state.add_offroad_transition_callback(self._offroad_transition) def _offroad_transition(self): - # Reconnect if not first time going onroad - if ui_state.is_onroad() and self.frame is not None: - # Prevent old frames from showing when going onroad. Qt has a separate thread - # which drains the VisionIpcClient SubSocket for us. Re-connecting is not enough - # and only clears internal buffers, not the message queue. - self.available_streams.clear() - if self.client: - del self.client - self.client = VisionIpcClient(self._name, self._stream_type, conflate=True) + # Drain queued SubSocket messages to prevent old frames from showing when going + # onroad. Qt had a separate thread which drains the VisionIpcClient SubSocket for us. + if self.client and self.client.is_connected(): + while self.client.recv(timeout_ms=0) is not None: + pass self.frame = None def _set_placeholder_color(self, color: rl.Color): @@ -312,8 +308,8 @@ class CameraView(Widget): 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)) + rl.update_texture(self.texture_y, rl.ffi.cast("void *", rl.ffi.from_buffer(y_data))) + rl.update_texture(self.texture_uv, rl.ffi.cast("void *", rl.ffi.from_buffer(uv_data))) self._texture_needs_update = False # Render with shader diff --git a/selfdrive/ui/mici/onroad/driver_camera_dialog.py b/selfdrive/ui/mici/onroad/driver_camera_dialog.py index e8321b099c..df5afe2e7c 100644 --- a/selfdrive/ui/mici/onroad/driver_camera_dialog.py +++ b/selfdrive/ui/mici/onroad/driver_camera_dialog.py @@ -1,20 +1,15 @@ import pyray as rl -from cereal import log, messaging +from cereal import car, log, messaging from msgq.visionipc import VisionStreamType from openpilot.selfdrive.ui.mici.onroad.cameraview import CameraView from openpilot.selfdrive.ui.mici.onroad.driver_state import DriverStateRenderer from openpilot.selfdrive.ui.ui_state import ui_state, device -from openpilot.selfdrive.selfdrived.events import EVENTS, ET from openpilot.system.ui.lib.application import gui_app, FontWeight from openpilot.system.ui.lib.multilang import tr from openpilot.system.ui.widgets import Widget from openpilot.system.ui.widgets.nav_widget import NavWidget from openpilot.system.ui.widgets.label import gui_label -EventName = log.OnroadEvent.EventName - -EVENT_TO_INT = EventName.schema.enumerants - class DriverCameraView(CameraView): def _calc_frame_matrix(self, rect: rl.Rectangle): @@ -109,11 +104,14 @@ class BaseDriverCameraDialog(Widget): if self._pm is None: return + AudibleAlert = car.CarControl.HUDControl.AudibleAlert + ALERT_SOUNDS = { + 'two': AudibleAlert.promptDistracted, + 'three': AudibleAlert.warningImmediate, + } msg = messaging.new_message('selfdriveState') - if dm_state is not None and len(dm_state.events): - event_name = EVENT_TO_INT[dm_state.events[0].name] - if event_name is not None and event_name in EVENTS and ET.PERMANENT in EVENTS[event_name]: - msg.selfdriveState.alertSound = EVENTS[event_name][ET.PERMANENT].audible_alert + if dm_state is not None: + msg.selfdriveState.alertSound = ALERT_SOUNDS.get(str(dm_state.alertLevel), AudibleAlert.none) self._pm.send('selfdriveState', msg) def _render_dm_alerts(self, rect: rl.Rectangle): @@ -121,29 +119,31 @@ class BaseDriverCameraDialog(Widget): dm_state = ui_state.sm["driverMonitoringState"] self._publish_alert_sound(dm_state) + is_vision = dm_state.activePolicy == log.DriverMonitoringState.MonitoringPolicy.vision + awareness_pct = dm_state.visionPolicyState.awarenessPercent if is_vision else dm_state.wheeltouchPolicyState.awarenessPercent gui_label(rl.Rectangle(rect.x + 2, rect.y + 2, rect.width, rect.height), - f"Awareness: {dm_state.awarenessStatus * 100:.0f}%", font_size=44, font_weight=FontWeight.MEDIUM, + f"Awareness: {awareness_pct:.0f}%", font_size=44, font_weight=FontWeight.MEDIUM, alignment=rl.GuiTextAlignment.TEXT_ALIGN_RIGHT, alignment_vertical=rl.GuiTextAlignmentVertical.TEXT_ALIGN_TOP, color=rl.Color(0, 0, 0, 180)) - gui_label(rect, f"Awareness: {dm_state.awarenessStatus * 100:.0f}%", font_size=44, font_weight=FontWeight.MEDIUM, + gui_label(rect, f"Awareness: {awareness_pct:.0f}%", font_size=44, font_weight=FontWeight.MEDIUM, alignment=rl.GuiTextAlignment.TEXT_ALIGN_RIGHT, alignment_vertical=rl.GuiTextAlignmentVertical.TEXT_ALIGN_TOP, color=rl.Color(255, 255, 255, int(255 * 0.9))) - if not dm_state.events: + if dm_state.alertLevel == log.DriverMonitoringState.AlertLevel.none: return - # Show first event (only one should be active at a time) - event_name_str = str(dm_state.events[0].name).split('.')[-1] + # Show alert level + alert_level_str = f"{'Pay Attention' if is_vision else 'Touch Wheel'} - level {dm_state.alertLevel}" alignment = rl.GuiTextAlignment.TEXT_ALIGN_RIGHT if self.driver_state_renderer.is_rhd else rl.GuiTextAlignment.TEXT_ALIGN_LEFT shadow_rect = rl.Rectangle(rect.x + 2, rect.y + 2, rect.width, rect.height) - gui_label(shadow_rect, event_name_str, font_size=40, font_weight=FontWeight.BOLD, + gui_label(shadow_rect, alert_level_str, font_size=40, font_weight=FontWeight.BOLD, alignment=alignment, alignment_vertical=rl.GuiTextAlignmentVertical.TEXT_ALIGN_BOTTOM, color=rl.Color(0, 0, 0, 180)) - gui_label(rect, event_name_str, font_size=40, font_weight=FontWeight.BOLD, + gui_label(rect, alert_level_str, font_size=40, font_weight=FontWeight.BOLD, alignment=alignment, alignment_vertical=rl.GuiTextAlignmentVertical.TEXT_ALIGN_BOTTOM, color=rl.Color(255, 255, 255, int(255 * 0.9))) @@ -160,7 +160,7 @@ class BaseDriverCameraDialog(Widget): def _draw_face_detection(self, rect: rl.Rectangle): dm_state = ui_state.sm["driverMonitoringState"] driver_data = self.driver_state_renderer.get_driver_data() - if not dm_state.faceDetected: + if not dm_state.visionPolicyState.faceDetected: return # Get face position and orientation diff --git a/selfdrive/ui/mici/onroad/driver_state.py b/selfdrive/ui/mici/onroad/driver_state.py index b2be5a8e34..1855d77b77 100644 --- a/selfdrive/ui/mici/onroad/driver_state.py +++ b/selfdrive/ui/mici/onroad/driver_state.py @@ -6,7 +6,7 @@ from openpilot.common.filter_simple import FirstOrderFilter from openpilot.system.ui.lib.application import gui_app from openpilot.system.ui.widgets import Widget from openpilot.selfdrive.ui.ui_state import ui_state -from openpilot.selfdrive.monitoring.helpers import face_orientation_from_net + AlertSize = log.SelfdriveState.AlertSize @@ -16,11 +16,15 @@ DEBUG = False LOOKING_CENTER_THRESHOLD_UPPER = math.radians(6) LOOKING_CENTER_THRESHOLD_LOWER = math.radians(3) +CONE_COLOR_GREEN = (0, 255, 64) +CONE_COLOR_ORANGE = (255, 115, 0) + class DriverStateRenderer(Widget): BASE_SIZE = 60 LINES_ANGLE_INCREMENT = 5 LINES_STALE_ANGLES = 3.0 # seconds + AWARENESS_UNFULL_PERCENT = 95 # ~0.5s def __init__(self, lines: bool = False, inset: bool = False): super().__init__() @@ -35,11 +39,15 @@ class DriverStateRenderer(Widget): self._is_active = False self._is_rhd = False self._face_detected = False + self._face_pitch = 0. + self._face_yaw = 0. self._should_draw = False self._force_active = False self._looking_center = False + self._awareness_unfull = False self._fade_filter = FirstOrderFilter(0.0, 0.05, 1 / gui_app.target_fps) + self._color_fade_filter = FirstOrderFilter(1.0, 0.05, 1 / gui_app.target_fps) # 1.0 = full green, 0.0 = full orange self._pitch_filter = FirstOrderFilter(0.0, 0.05, 1 / gui_app.target_fps, initialized=False) self._yaw_filter = FirstOrderFilter(0.0, 0.05, 1 / gui_app.target_fps, initialized=False) self._rotation_filter = FirstOrderFilter(0.0, 0.1, 1 / gui_app.target_fps, initialized=False) @@ -97,6 +105,7 @@ class DriverStateRenderer(Widget): self._rect.y + (self._rect.height - self._dm_person.height) / 2), 0.0, 1.0, rl.Color(255, 255, 255, int(255 * 0.9 * self._fade_filter.x))) + green_amount = self._color_fade_filter.update(0.0 if self._awareness_unfull else 1.0) if self.effective_active: source_rect = rl.Rectangle(0, 0, self._dm_cone.width, self._dm_cone.height) dest_rect = rl.Rectangle( @@ -107,13 +116,16 @@ class DriverStateRenderer(Widget): ) if not self._lines: + r = int(round(CONE_COLOR_GREEN[0] * green_amount + CONE_COLOR_ORANGE[0] * (1 - green_amount))) + g = int(round(CONE_COLOR_GREEN[1] * green_amount + CONE_COLOR_ORANGE[1] * (1 - green_amount))) + b = int(round(CONE_COLOR_GREEN[2] * green_amount + CONE_COLOR_ORANGE[2] * (1 - green_amount))) rl.draw_texture_pro( self._dm_cone, source_rect, dest_rect, rl.Vector2(dest_rect.width / 2, dest_rect.height / 2), self._rotation_filter.x - 90, - rl.Color(255, 255, 255, int(255 * self._fade_filter.x)), + rl.Color(r, g, b, int(255 * self._fade_filter.x)), ) else: @@ -153,9 +165,12 @@ class DriverStateRenderer(Widget): sm = ui_state.sm dm_state = sm["driverMonitoringState"] - self._is_active = dm_state.isActiveMode + self._is_active = dm_state.activePolicy == log.DriverMonitoringState.MonitoringPolicy.vision self._is_rhd = dm_state.isRHD - self._face_detected = dm_state.faceDetected + self._face_detected = dm_state.visionPolicyState.faceDetected + self._awareness_unfull = self.effective_active and dm_state.visionPolicyState.awarenessPercent < self.AWARENESS_UNFULL_PERCENT + self._face_pitch = dm_state.visionPolicyState.pose.pitch + math.radians(6) # calib or DM pose is not accurate, add a fake upward pitch to bias forward + self._face_yaw = -dm_state.visionPolicyState.pose.yaw # undo sign flip in face_orientation_from_model to match UI convention driverstate = sm["driverStateV2"] driver_data = driverstate.rightDriverData if self._is_rhd else driverstate.leftDriverData @@ -163,26 +178,9 @@ class DriverStateRenderer(Widget): def _update_state(self): # Get monitoring state - driver_data = self.get_driver_data() - driver_orient = driver_data.faceOrientation - driver_position = driver_data.facePosition - - if len(driver_orient) != 3: - return - - # Calibrate orientation so looking straight ahead at road (instead of at device) is (0, 0, 0) - sm = ui_state.sm - if sm.valid['liveCalibration'] and len(sm['liveCalibration'].rpyCalib) == 3: - cal_rpy = sm['liveCalibration'].rpyCalib - else: - cal_rpy = [0.0, 0.0, 0.0] - - _, pitch, yaw = face_orientation_from_net(driver_orient, driver_position, cal_rpy) - pitch += math.radians(6) # calib or DM pose is not accurate, add a fake upward pitch to bias forward - yaw = -yaw # undo sign flip in face_orientation_from_net to match UI convention - - pitch = self._pitch_filter.update(pitch) - yaw = self._yaw_filter.update(yaw) + _ = self.get_driver_data() + pitch = self._pitch_filter.update(self._face_pitch) + yaw = self._yaw_filter.update(self._face_yaw) # hysteresis on looking center if abs(pitch) < LOOKING_CENTER_THRESHOLD_LOWER and abs(yaw) < LOOKING_CENTER_THRESHOLD_LOWER: diff --git a/selfdrive/ui/mici/onroad/hud_renderer.py b/selfdrive/ui/mici/onroad/hud_renderer.py index 76724244d0..c74d3101b0 100644 --- a/selfdrive/ui/mici/onroad/hud_renderer.py +++ b/selfdrive/ui/mici/onroad/hud_renderer.py @@ -235,7 +235,7 @@ class HudRenderer(Widget): # draw drop shadow circle_radius = 162 // 2 - rl.draw_circle_gradient(int(x + circle_radius), int(y + circle_radius), circle_radius, + rl.draw_circle_gradient(rl.Vector2(x + circle_radius, y + circle_radius), circle_radius, rl.Color(0, 0, 0, int(255 / 2 * alpha)), rl.BLANK) set_speed_color = rl.Color(255, 255, 255, int(255 * 0.9 * alpha)) diff --git a/selfdrive/ui/mici/onroad/model_renderer.py b/selfdrive/ui/mici/onroad/model_renderer.py index ca051c6d94..e88d320a3f 100644 --- a/selfdrive/ui/mici/onroad/model_renderer.py +++ b/selfdrive/ui/mici/onroad/model_renderer.py @@ -76,7 +76,7 @@ class ModelRenderer(Widget, ModelRendererSP): self._torque_filter = FirstOrderFilter(0, 0.1, 1 / gui_app.target_fps) self._ll_color_filter = FirstOrderFilter(0.0, 0.1, 1 / gui_app.target_fps) - # Transform matrix (3x3 for car space to screen space) + # 3x3 car space -> rect-origin space (draw methods add rect.x/y) self._car_space_transform = np.zeros((3, 3), dtype=np.float32) self._transform_dirty = True self._clip_region = None @@ -232,7 +232,8 @@ class ModelRenderer(Widget, ModelRendererSP): if not self._experimental_mode: return - max_len = min(len(self._path.projected_points) // 2, len(self._acceleration_x)) + path_pts = self._path.projected_points + np.array([self._rect.x, self._rect.y], dtype=np.float32) + max_len = min(len(path_pts) // 2, len(self._acceleration_x)) segment_colors = [] gradient_stops = [] @@ -240,7 +241,7 @@ class ModelRenderer(Widget, ModelRendererSP): i = 0 while i < max_len: # Some points (screen space) are out of frame (rect space) - track_y = self._path.projected_points[i][1] + track_y = path_pts[i][1] if track_y < self._rect.y or track_y > (self._rect.y + self._rect.height): i += 1 continue @@ -316,14 +317,15 @@ class ModelRenderer(Widget, ModelRendererSP): return color def _draw_lane_lines(self): - """Draw lane lines and road edges""" - """Two closest lines should be green (lane line or road edges)""" + """Draw lane lines and road edges. Two closest lines should be green (lane line or road edges).""" + offset = np.array([self._rect.x, self._rect.y], dtype=np.float32) + for i, lane_line in enumerate(self._lane_lines): if lane_line.projected_points.size == 0: continue color = self._get_ll_color(float(self._lane_line_probs[i]), i in (1, 2), i in (0, 1)) - draw_polygon(self._rect, lane_line.projected_points, color) + draw_polygon(self._rect, lane_line.projected_points + offset, color) for i, road_edge in enumerate(self._road_edges): if road_edge.projected_points.size == 0: @@ -331,7 +333,7 @@ class ModelRenderer(Widget, ModelRendererSP): # if closest lane lines are not confident, make road edges green color = self._get_ll_color(float(1.0 - self._road_edge_stds[i]), float(self._lane_line_probs[i + 1]) < 0.25, i == 0) - draw_polygon(self._rect, road_edge.projected_points, color) + draw_polygon(self._rect, road_edge.projected_points + offset, color) def _draw_path(self, sm): """Draw path with dynamic coloring based on mode and throttle state.""" @@ -345,14 +347,16 @@ class ModelRenderer(Widget, ModelRendererSP): self.rainbow_path.draw_rainbow_path(self._rect, self._path) return + path_pts = self._path.projected_points + np.array([self._rect.x, self._rect.y], dtype=np.float32) + if self._experimental_mode: # Draw with acceleration coloring if ui_state.status == UIStatus.DISENGAGED: - draw_polygon(self._rect, self._path.projected_points, rl.Color(0, 0, 0, 90)) + draw_polygon(self._rect, path_pts, rl.Color(0, 0, 0, 90)) elif len(self._exp_gradient.colors) > 1: - draw_polygon(self._rect, self._path.projected_points, gradient=self._exp_gradient) + draw_polygon(self._rect, path_pts, gradient=self._exp_gradient) else: - draw_polygon(self._rect, self._path.projected_points, rl.Color(255, 255, 255, 30)) + draw_polygon(self._rect, path_pts, rl.Color(255, 255, 255, 30)) else: # Blend throttle/no throttle colors based on transition blend_factor = round(self._blend_filter.x * 100) / 100 @@ -365,9 +369,9 @@ class ModelRenderer(Widget, ModelRendererSP): ) if ui_state.status == UIStatus.DISENGAGED: - draw_polygon(self._rect, self._path.projected_points, rl.Color(0, 0, 0, 90)) + draw_polygon(self._rect, path_pts, rl.Color(0, 0, 0, 90)) else: - draw_polygon(self._rect, self._path.projected_points, gradient=gradient) + draw_polygon(self._rect, path_pts, gradient=gradient) def _draw_lead_indicator(self): # Draw lead vehicles if available diff --git a/selfdrive/ui/mici/onroad/torque_bar.py b/selfdrive/ui/mici/onroad/torque_bar.py index f0690c0abf..861bfe493e 100644 --- a/selfdrive/ui/mici/onroad/torque_bar.py +++ b/selfdrive/ui/mici/onroad/torque_bar.py @@ -23,9 +23,9 @@ def quantized_lru_cache(maxsize=128): def decorator(func): cache = OrderedDict() @wraps(func) - def wrapper(cx, cy, r_mid, thickness, a0_deg, a1_deg, **kwargs): + def wrapper(r_mid, thickness, a0_deg, a1_deg, **kwargs): # Quantize inputs: balanced for smoothness vs cache effectiveness - key = (round(cx), round(cy), round(r_mid), + key = (round(r_mid), round(thickness), # 1px precision for smoother height transitions round(a0_deg * 10) / 10, # 0.1° precision for smoother angle transitions round(a1_deg * 10) / 10, @@ -37,7 +37,7 @@ def quantized_lru_cache(maxsize=128): if len(cache) >= maxsize: cache.popitem(last=False) - result = func(cx, cy, r_mid, thickness, a0_deg, a1_deg, **kwargs) + result = func(r_mid, thickness, a0_deg, a1_deg, **kwargs) cache[key] = result return cache[key] return wrapper @@ -45,12 +45,11 @@ def quantized_lru_cache(maxsize=128): @quantized_lru_cache(maxsize=256) -def arc_bar_pts(cx: float, cy: float, - r_mid: float, thickness: float, +def arc_bar_pts(r_mid: float, thickness: float, a0_deg: float, a1_deg: float, *, max_points: int = 100, cap_segs: int = 10, cap_radius: float = 7, px_per_seg: float = 2.0) -> np.ndarray: - """Return Nx2 np.float32 points for a single closed polygon (rounded thick arc).""" + """Return Nx2 np.float32 points for a single closed polygon (rounded thick arc), centered at origin.""" def get_cap(left: bool, a_deg: float): # end cap at a1: center (a1), sweep a1→a1+180 (skip endpoints to avoid dupes) @@ -59,7 +58,7 @@ def arc_bar_pts(cx: float, cy: float, nx, ny = math.cos(math.radians(a_deg)), math.sin(math.radians(a_deg)) # outward normal tx, ty = -ny, nx # tangent (CCW) - mx, my = cx + nx * r_mid, cy + ny * r_mid # mid-point at a1 + mx, my = nx * r_mid, ny * r_mid # mid-point at a1 if DEBUG: rl.draw_circle(int(mx), int(my), 4, rl.PURPLE) @@ -114,16 +113,16 @@ def arc_bar_pts(cx: float, cy: float, # outer arc a0→a1 ang_o = np.deg2rad(np.linspace(a0_deg, a1_deg, arc_segs + 1)) - outer = np.c_[cx + np.cos(ang_o) * (r_mid + half), - cy + np.sin(ang_o) * (r_mid + half)] + outer = np.c_[np.cos(ang_o) * (r_mid + half), + np.sin(ang_o) * (r_mid + half)] # end cap at a1 cap_end = get_cap(False, a1_deg) # inner arc a1→a0 ang_i = np.deg2rad(np.linspace(a1_deg, a0_deg, arc_segs + 1)) - inner = np.c_[cx + np.cos(ang_i) * (r_mid - half), - cy + np.sin(ang_i) * (r_mid - half)] + inner = np.c_[np.cos(ang_i) * (r_mid - half), + np.sin(ang_i) * (r_mid - half)] # start cap at a0 cap_start = get_cap(True, a0_deg) @@ -217,15 +216,16 @@ class TorqueBar(Widget): cx = rect.x + rect.width / 2 + 8 # offset 8px to right of camera feed cy = rect.y + rect.height + torque_line_radius - torque_line_offset + offset = np.array([cx, cy], dtype=np.float32) # draw bg torque indicator line - bg_pts = arc_bar_pts(cx, cy, mid_r, torque_line_height, torque_start_angle, torque_end_angle, cap_radius=7 * self._scale) + bg_pts = arc_bar_pts(mid_r, torque_line_height, torque_start_angle, torque_end_angle, cap_radius=7 * self._scale) + offset draw_polygon(rect, bg_pts, color=torque_line_bg_color) # draw torque indicator line a0s = top_angle a1s = a0s + torque_bg_angle_span / 2 * self._torque_filter.x - sl_pts = arc_bar_pts(cx, cy, mid_r, torque_line_height, a0s, a1s, cap_radius=7 * self._scale) + sl_pts = arc_bar_pts(mid_r, torque_line_height, a0s, a1s, cap_radius=7 * self._scale) + offset # draw beautiful gradient from center to 65% of the bg torque bar width start_grad_pt = cx / rect.width diff --git a/selfdrive/ui/mici/widgets/button.py b/selfdrive/ui/mici/widgets/button.py index 058c351fb6..1dceb79691 100644 --- a/selfdrive/ui/mici/widgets/button.py +++ b/selfdrive/ui/mici/widgets/button.py @@ -387,7 +387,7 @@ class BigMultiParamToggle(BigMultiToggle): def _handle_mouse_release(self, mouse_pos: MousePos): super()._handle_mouse_release(mouse_pos) new_idx = self._options.index(self.value) - self._params.put_nonblocking(self._param, new_idx) + self._params.put(self._param, new_idx) class BigParamControl(BigToggle): @@ -399,7 +399,7 @@ class BigParamControl(BigToggle): def _handle_mouse_release(self, mouse_pos: MousePos): super()._handle_mouse_release(mouse_pos) - self.params.put_bool(self.param, self._checked) + self.params.put_bool(self.param, self._checked, block=True) def refresh(self): self.set_checked(self.params.get_bool(self.param, False)) @@ -416,7 +416,7 @@ class BigCircleParamControl(BigCircleToggle): def _handle_mouse_release(self, mouse_pos: MousePos): super()._handle_mouse_release(mouse_pos) - self.params.put_bool(self._param, self._checked) + self.params.put_bool(self._param, self._checked, block=True) def refresh(self): self.set_checked(self.params.get_bool(self._param, False)) diff --git a/selfdrive/ui/onroad/augmented_road_view.py b/selfdrive/ui/onroad/augmented_road_view.py index 8abc8fbb52..21511412e6 100644 --- a/selfdrive/ui/onroad/augmented_road_view.py +++ b/selfdrive/ui/onroad/augmented_road_view.py @@ -1,7 +1,6 @@ -import time import numpy as np import pyray as rl -from cereal import log, messaging +from cereal import log from msgq.visionipc import VisionStreamType from openpilot.selfdrive.ui import UI_BORDER_SIZE from openpilot.selfdrive.ui.ui_state import ui_state, UIStatus @@ -58,12 +57,8 @@ class AugmentedRoadView(CameraView, AugmentedRoadViewSP): self.alert_renderer = AlertRenderer() self.driver_state_renderer = DriverStateRenderer() - # debug - self._pm = messaging.PubMaster(['uiDebug']) - def _render(self, rect): # Only render when system is started to avoid invalid data access - start_draw = time.monotonic() if not ui_state.started: return @@ -108,11 +103,6 @@ class AugmentedRoadView(CameraView, AugmentedRoadViewSP): # Draw colored border based on driving state self._draw_border(rect) - # publish uiDebug - msg = messaging.new_message('uiDebug') - msg.uiDebug.drawTimeMillis = (time.monotonic() - start_draw) * 1000 - self._pm.send('uiDebug', msg) - def _handle_mouse_press(self, _): if not self._hud_renderer.user_interacting() and self._click_callback is not None: self._click_callback() diff --git a/selfdrive/ui/onroad/cameraview.py b/selfdrive/ui/onroad/cameraview.py index 5443948465..53c2ff8b0b 100644 --- a/selfdrive/ui/onroad/cameraview.py +++ b/selfdrive/ui/onroad/cameraview.py @@ -267,8 +267,8 @@ class CameraView(Widget): 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)) + rl.update_texture(self.texture_y, rl.ffi.cast("void *", rl.ffi.from_buffer(y_data))) + rl.update_texture(self.texture_uv, rl.ffi.cast("void *", rl.ffi.from_buffer(uv_data))) self._texture_needs_update = False # Render with shader diff --git a/selfdrive/ui/onroad/driver_camera_dialog.py b/selfdrive/ui/onroad/driver_camera_dialog.py index e66e04b824..7e07e44210 100644 --- a/selfdrive/ui/onroad/driver_camera_dialog.py +++ b/selfdrive/ui/onroad/driver_camera_dialog.py @@ -15,11 +15,11 @@ class DriverCameraDialog(CameraView): self.driver_state_renderer = DriverStateRenderer() # TODO: this can grow unbounded, should be given some thought device.add_interactive_timeout_callback(gui_app.pop_widget) - ui_state.params.put_bool("IsDriverViewEnabled", True) + ui_state.params.put_bool("IsDriverViewEnabled", True, block=True) def hide_event(self): super().hide_event() - ui_state.params.put_bool("IsDriverViewEnabled", False) + ui_state.params.put_bool("IsDriverViewEnabled", False, block=True) self.close() def _handle_mouse_release(self, _): diff --git a/selfdrive/ui/onroad/driver_state.py b/selfdrive/ui/onroad/driver_state.py index 7b3181d1ac..5b09e471b5 100644 --- a/selfdrive/ui/onroad/driver_state.py +++ b/selfdrive/ui/onroad/driver_state.py @@ -114,7 +114,7 @@ class DriverStateRenderer(Widget): # Get monitoring state dm_state = sm["driverMonitoringState"] - self.is_active = dm_state.isActiveMode + self.is_active = dm_state.activePolicy == log.DriverMonitoringState.MonitoringPolicy.vision self.is_rhd = dm_state.isRHD # Update fade state (smoother transition between active/inactive) diff --git a/selfdrive/ui/sunnypilot/layouts/settings/models.py b/selfdrive/ui/sunnypilot/layouts/settings/models.py index 81f1c47db2..587c3560c9 100644 --- a/selfdrive/ui/sunnypilot/layouts/settings/models.py +++ b/selfdrive/ui/sunnypilot/layouts/settings/models.py @@ -152,7 +152,7 @@ class ModelsLayout(Widget): status_changed = self.prev_download_status != self.download_status self.prev_download_status = self.download_status - self.cancel_download_item.set_visible(bool(self.model_manager.selectedBundle) and bool(ui_state.params.get("ModelManager_DownloadIndex"))) + self.cancel_download_item.set_visible(bool(self.model_manager.selectedBundle) and ui_state.params.get("ModelManager_DownloadIndex") is not None) if (current_time := time.monotonic()) - self.last_cache_calc_time > 0.5: self.last_cache_calc_time = current_time diff --git a/selfdrive/ui/sunnypilot/mici/layouts/models.py b/selfdrive/ui/sunnypilot/mici/layouts/models.py index 7f3d9a065b..138ff87b75 100644 --- a/selfdrive/ui/sunnypilot/mici/layouts/models.py +++ b/selfdrive/ui/sunnypilot/mici/layouts/models.py @@ -170,7 +170,7 @@ class ModelsLayoutMici(NavScroller): self._was_downloading = is_downloading self.current_model_info.current_model_header.set_text(tr("active model")) - model_text = manager.activeBundle.displayName.lower() if manager.activeBundle.index > 0 else f"{DEFAULT_MODEL} (Default)".lower() + model_text = manager.activeBundle.displayName.lower() if manager.activeBundle.ref else f"{DEFAULT_MODEL} (Default)".lower() self.current_model_info.current_model_text.set_text(model_text) self.current_model_info.info_header.set_text(tr("cache size")) self.current_model_info.info_text.set_text(f"{ModelsLayout.calculate_cache_size():.2f} MB") diff --git a/selfdrive/ui/sunnypilot/onroad/speed_limit.py b/selfdrive/ui/sunnypilot/onroad/speed_limit.py index 98f5b29087..346262b86c 100644 --- a/selfdrive/ui/sunnypilot/onroad/speed_limit.py +++ b/selfdrive/ui/sunnypilot/onroad/speed_limit.py @@ -75,7 +75,7 @@ class SpeedLimitAlertRenderer: speed_limit_final_last = ui_state.sm['longitudinalPlanSP'].speedLimit.resolver.speedLimitFinalLast v_cruise_cluster = ui_state.sm['carState'].vCruiseCluster - set_speed = ui_state.sm['controlsState'].vCruiseDEPRECATED if v_cruise_cluster == 0.0 else v_cruise_cluster + set_speed = ui_state.sm['controlsState'].deprecated.vCruise if v_cruise_cluster == 0.0 else v_cruise_cluster if not ui_state.is_metric: set_speed *= KM_TO_MILE @@ -164,7 +164,7 @@ class SpeedLimitRenderer(Widget, SpeedLimitAlertRenderer): v_cruise_cluster = car_state.vCruiseCluster self.set_speed = ( - controls_state.vCruiseDEPRECATED if v_cruise_cluster == 0.0 else v_cruise_cluster + controls_state.deprecated.vCruise if v_cruise_cluster == 0.0 else v_cruise_cluster ) self.is_cruise_set = 0 < self.set_speed < SET_SPEED_NA self.is_cruise_available = self.set_speed != -1 diff --git a/selfdrive/ui/sunnypilot/ui_state.py b/selfdrive/ui/sunnypilot/ui_state.py index 2cfd5bd4f2..8cd37583f3 100644 --- a/selfdrive/ui/sunnypilot/ui_state.py +++ b/selfdrive/ui/sunnypilot/ui_state.py @@ -37,8 +37,25 @@ class UIStateSP: self.sunnylink_state = SunnylinkState() - self.onroad_brightness_timer: int = 0 + self.active_bundle = None + self.blindspot: bool = False + self.chevron_metrics = None self.custom_interactive_timeout: int = 0 + self.developer_ui = None + self.hide_v_ego_ui: bool = False + self.onroad_brightness: int = 0 + self.onroad_brightness_timer: int = 0 + self.onroad_brightness_timer_param: int = 0 + self.rainbow_path: bool = False + self.road_name_toggle: bool = False + self.rocket_fuel: bool = False + self.speed_limit_mode = None + self.standstill_timer: bool = False + self.sunnylink_enabled: bool = False + self.torque_bar: bool = False + self.enforce_torque_control: bool = False + self.custom_torque_params: bool = False + self.torque_override_enabled: bool = False self._sp_initialized: bool = False def update(self) -> None: diff --git a/selfdrive/ui/tests/cycle_offroad_alerts.py b/selfdrive/ui/tests/cycle_offroad_alerts.py index b577b74b00..fcb4a72c77 100755 --- a/selfdrive/ui/tests/cycle_offroad_alerts.py +++ b/selfdrive/ui/tests/cycle_offroad_alerts.py @@ -18,11 +18,11 @@ if __name__ == "__main__": t = 10 if len(sys.argv) < 2 else int(sys.argv[1]) while True: print("setting alert update") - params.put_bool("UpdateAvailable", True) - params.put("UpdaterNewReleaseNotes", parse_release_notes(BASEDIR)) + params.put_bool("UpdateAvailable", True, block=True) + params.put("UpdaterNewReleaseNotes", parse_release_notes(BASEDIR), block=True) time.sleep(t) - params.put_bool("UpdateAvailable", False) + params.put_bool("UpdateAvailable", False, block=True) # cycle through normal alerts for a in offroad_alerts: diff --git a/selfdrive/ui/tests/diff/replay.py b/selfdrive/ui/tests/diff/replay.py index fd82e325a3..cb88ee9da8 100755 --- a/selfdrive/ui/tests/diff/replay.py +++ b/selfdrive/ui/tests/diff/replay.py @@ -24,20 +24,19 @@ HEADLESS = os.getenv("WINDOWED", "0") != "1" def setup_state(): params = Params() - params.put("HasAcceptedTerms", terms_version) - params.put("CompletedTrainingVersion", training_version) - params.put("DongleId", "test123456789") + params.put("HasAcceptedTerms", terms_version, block=True) + params.put("CompletedTrainingVersion", training_version, block=True) + params.put("DongleId", "test123456789", block=True) # Combined description for layouts that still use it (BIG home, settings/software) - params.put("UpdaterCurrentDescription", "0.10.1 / test-branch / abc1234 / Nov 30") - params.put("UpdaterCurrentReleaseNotes", parse_release_notes(BASEDIR)) - params.put("HasAcceptedTermsSP", terms_version_sp) - params.put("CompletedSunnylinkConsentVersion", sunnylink_consent_version) - + params.put("UpdaterCurrentDescription", "0.10.1 / test-branch / abc1234 / Nov 30", block=True) + params.put("UpdaterCurrentReleaseNotes", parse_release_notes(BASEDIR), block=True) + params.put("HasAcceptedTermsSP", terms_version_sp, block=True) + params.put("CompletedSunnylinkConsentVersion", sunnylink_consent_version, block=True) # Params for mici home - params.put("Version", "0.10.1") - params.put("GitBranch", "test-branch") - params.put("GitCommit", "abc12340ff9131237ba23a1d0fbd8edf9c80e87") - params.put("GitCommitDate", "'1732924800 2024-11-30 00:00:00 +0000'") + params.put("Version", "0.10.1", block=True) + params.put("GitBranch", "test-branch", block=True) + params.put("GitCommit", "abc12340ff9131237ba23a1d0fbd8edf9c80e87", block=True) + params.put("GitCommitDate", "'1732924800 2024-11-30 00:00:00 +0000'", block=True) # Patch Api.get_token to return a static token so the pairing QR code is deterministic across runs Api.get_token = lambda self, payload_extra=None, expiry_hours=0: "test_token" diff --git a/selfdrive/ui/tests/diff/replay_script.py b/selfdrive/ui/tests/diff/replay_script.py index c53d2f116b..ad7e8952d6 100644 --- a/selfdrive/ui/tests/diff/replay_script.py +++ b/selfdrive/ui/tests/diff/replay_script.py @@ -126,12 +126,12 @@ def setup_offroad_alerts() -> None: def setup_update_available(available: bool = True) -> None: params = Params() - params.put_bool("UpdateAvailable", available) - params.put("UpdaterAvailableBranches", ",".join(["test-branch", "test-branch-2", BRANCH_NAME])) + params.put_bool("UpdateAvailable", available, block=True) + params.put("UpdaterAvailableBranches", ",".join(["test-branch", "test-branch-2", BRANCH_NAME]), block=True) if available: - params.put("UpdaterNewDescription", f"0.10.2 / {BRANCH_NAME} / 0a1b2c3 / Jan 01") - params.put("UpdaterNewReleaseNotes", parse_release_notes(BASEDIR)) - params.put("UpdaterTargetBranch", BRANCH_NAME) + params.put("UpdaterNewDescription", f"0.10.2 / {BRANCH_NAME} / 0a1b2c3 / Jan 01", block=True) + params.put("UpdaterNewReleaseNotes", parse_release_notes(BASEDIR), block=True) + params.put("UpdaterTargetBranch", BRANCH_NAME, block=True) else: params.remove("UpdaterNewDescription") params.remove("UpdaterNewReleaseNotes") @@ -144,22 +144,22 @@ def setup_calibration_params() -> None: calib = messaging.new_message('liveCalibration') calib.liveCalibration.calStatus = log.LiveCalibrationData.Status.calibrated calib.liveCalibration.rpyCalib = [0.0, math.radians(2.5), math.radians(-1.2)] - params.put("CalibrationParams", calib.to_bytes()) + params.put("CalibrationParams", calib.to_bytes(), block=True) # live delay delay = messaging.new_message('liveDelay') delay.liveDelay.calPerc = 75 - params.put("LiveDelay", delay.to_bytes()) + params.put("LiveDelay", delay.to_bytes(), block=True) # live torque parameters torque = messaging.new_message('liveTorqueParameters') torque.liveTorqueParameters.useParams = True torque.liveTorqueParameters.calPerc = 60 - params.put("LiveTorqueParameters", torque.to_bytes()) + params.put("LiveTorqueParameters", torque.to_bytes(), block=True) def setup_developer_params() -> None: CP = car.CarParams() CP.alphaLongitudinalAvailable = True - Params().put("CarParamsPersistent", CP.to_bytes()) + Params().put("CarParamsPersistent", CP.to_bytes(), block=True) # --- Send functions --- @@ -354,7 +354,10 @@ def build_mici_script(pm: PubMaster, main_layout, script: Script) -> None: def setup_offroad_alerts_and_refresh() -> None: """Setup function to trigger offroad alerts and force a refresh on the alerts layout.""" setup_offroad_alerts() - main_layout._alerts_layout.refresh() + params = Params() + main_layout._alerts_layout._pending_params = ({"UpdaterNewDescription": params.get("UpdaterNewDescription")} | + {alert_data.key: params.get(alert_data.key) for alert_data in main_layout._alerts_layout.sorted_alerts}) + main_layout._alerts_layout._refresh() swipe_right(width, wait_after=WAIT_SHORT) # open alerts script.setup(setup_offroad_alerts_and_refresh) # show alerts diff --git a/selfdrive/ui/tests/test_feedbackd.py b/selfdrive/ui/tests/test_feedbackd.py index 6b7ec44863..0f7148de04 100644 --- a/selfdrive/ui/tests/test_feedbackd.py +++ b/selfdrive/ui/tests/test_feedbackd.py @@ -27,7 +27,7 @@ class TestFeedbackd: @pytest.mark.parametrize("record_feedback", [False, True]) def test_audio_feedback(self, record_feedback): - Params().put_bool("RecordAudioFeedback", record_feedback) + Params().put_bool("RecordAudioFeedback", record_feedback, block=True) managed_processes["feedbackd"].start() assert self.pm.wait_for_readers_to_update('carState', timeout=5) diff --git a/selfdrive/ui/ui.py b/selfdrive/ui/ui.py index e3cac2618e..e01ddb2513 100755 --- a/selfdrive/ui/ui.py +++ b/selfdrive/ui/ui.py @@ -1,8 +1,10 @@ #!/usr/bin/env python3 import os +import time +from cereal import messaging from openpilot.system.hardware import TICI -from openpilot.common.realtime import config_realtime_process, set_core_affinity +from openpilot.common.realtime import Priority, config_realtime_process, set_core_affinity from openpilot.system.ui.lib.application import gui_app from openpilot.selfdrive.ui.layouts.main import MainLayout from openpilot.selfdrive.ui.mici.layouts.main import MiciMainLayout @@ -13,7 +15,8 @@ BIG_UI = gui_app.big_ui() def main(): cores = {5, } - config_realtime_process(0, 51) + # above plannerd and radard + config_realtime_process(0, Priority.CTRL_HIGH) gui_app.init_window("UI") if BIG_UI: @@ -21,8 +24,11 @@ def main(): else: MiciMainLayout() - for should_render in gui_app.render(): + pm = messaging.PubMaster(['uiDebug']) + for should_render, frame_time, cpu_time in gui_app.render(): + extra_start = time.monotonic() ui_state.update() + if should_render: # reaffine after power save offlines our core if TICI and os.sched_getaffinity(0) != cores: @@ -31,6 +37,12 @@ def main(): except OSError: pass + extra_cpu = time.monotonic() - extra_start + msg = messaging.new_message('uiDebug') + msg.uiDebug.cpuTimeMillis = (cpu_time + extra_cpu) * 1000 + msg.uiDebug.frameTimeMillis = frame_time * 1000 + pm.send('uiDebug', msg) + if __name__ == "__main__": main() diff --git a/selfdrive/ui/ui_state.py b/selfdrive/ui/ui_state.py index 64c0b88d1f..806dc11a6d 100644 --- a/selfdrive/ui/ui_state.py +++ b/selfdrive/ui/ui_state.py @@ -7,6 +7,7 @@ from enum import Enum from cereal import messaging, car, log from openpilot.common.filter_simple import FirstOrderFilter from openpilot.common.params import Params +from openpilot.common.realtime import drop_realtime from openpilot.common.swaglog import cloudlog from openpilot.selfdrive.ui.lib.prime_state import PrimeState from openpilot.system.ui.lib.application import gui_app @@ -15,6 +16,7 @@ from openpilot.system.hardware import HARDWARE, PC from openpilot.selfdrive.ui.sunnypilot.ui_state import UIStateSP, DeviceSP BACKLIGHT_OFFROAD = 65 if HARDWARE.get_device_type() == "mici" else 50 +PARAM_UPDATE_TIME = 1 / 5.0 class UIStatus(Enum): @@ -59,6 +61,7 @@ class UIState(UIStateSP): "carOutput", "carControl", "liveParameters", + "testJoystick", "rawAudioData", ] + self.sm_services_ext ) @@ -76,21 +79,25 @@ class UIState(UIStateSP): self.is_metric: bool = self.params.get_bool("IsMetric") self.is_release = False # self.params.get_bool("IsReleaseBranch") self.always_on_dm: bool = self.params.get_bool("AlwaysOnDM") + self.experimental_mode: bool = self.params.get_bool("ExperimentalMode") + self.usbgpu: bool = self.params.get_bool("UsbGpuPresent") + self.usbgpu_compiled: bool = self.params.get_bool("UsbGpuCompiled") self.started: bool = False self.ignition: bool = False self.recording_audio: bool = False self.panda_type: log.PandaState.PandaType = log.PandaState.PandaType.unknown self.personality: log.LongitudinalPersonality = log.LongitudinalPersonality.standard self.has_longitudinal_control: bool = False + self.is_body: bool | None = None self.CP: car.CarParams | None = None self.light_sensor: float = -1.0 - self._param_update_time: float = 0.0 + + self._params_thread: threading.Thread | None = None # Callbacks self._offroad_transition_callbacks: list[Callable[[], None]] = [] self._engaged_transition_callbacks: list[Callable[[], None]] = [] - - self.update_params() + self._on_body_changed_callbacks: list[Callable[[], None]] = [] def add_offroad_transition_callback(self, callback: Callable[[], None]): self._offroad_transition_callbacks.append(callback) @@ -98,6 +105,9 @@ class UIState(UIStateSP): def add_engaged_transition_callback(self, callback: Callable[[], None]): self._engaged_transition_callbacks.append(callback) + def add_on_body_changed_callbacks(self, callback: Callable[[], None]): + self._on_body_changed_callbacks.append(callback) + @property def engaged(self) -> bool: return self.started and (self.sm["selfdriveState"].enabled or self.sm["selfdriveStateSP"].mads.enabled) @@ -110,14 +120,22 @@ class UIState(UIStateSP): def update(self) -> None: self.prime_state.start() # start thread after manager forks ui + if self._params_thread is None: + self._params_thread = threading.Thread(target=self._params_refresh_worker, daemon=True) + self._params_thread.start() + self.sm.update(0) self._update_state() self._update_status() - if time.monotonic() - self._param_update_time > 5.0: - self.update_params() device.update() UIStateSP.update(self) + def _params_refresh_worker(self): + drop_realtime() + while True: + self.update_params() + time.sleep(PARAM_UPDATE_TIME) + def _update_state(self) -> None: # Handle panda states updates if self.sm.updated["pandaStates"]: @@ -142,11 +160,11 @@ class UIState(UIStateSP): # Update started state self.started = self.sm["deviceState"].started and self.ignition - # Update recording audio state - self.recording_audio = self.params.get_bool("RecordAudio") and self.started - - self.is_metric = self.params.get_bool("IsMetric") - self.always_on_dm = self.params.get_bool("AlwaysOnDM") + # Update body state + if self.CP is not None and self.is_body != self.CP.notCar: + self.is_body = self.CP.notCar + for callback in self._on_body_changed_callbacks: + callback() def _update_status(self) -> None: if self.started and self.sm.updated["selfdriveState"]: @@ -188,8 +206,15 @@ class UIState(UIStateSP): self.has_longitudinal_control = self.params.get_bool("AlphaLongitudinalEnabled") else: self.has_longitudinal_control = self.CP.openpilotLongitudinalControl + + self.recording_audio = self.params.get_bool("RecordAudio") and self.started + self.is_metric = self.params.get_bool("IsMetric") + self.always_on_dm = self.params.get_bool("AlwaysOnDM") + self.experimental_mode = self.params.get_bool("ExperimentalMode") + self.usbgpu = self.params.get_bool("UsbGpuPresent") + self.usbgpu_compiled = self.params.get_bool("UsbGpuCompiled") + UIStateSP.update_params(self) - self._param_update_time = time.monotonic() class Device(DeviceSP): @@ -206,6 +231,8 @@ class Device(DeviceSP): self._last_brightness: int = 0 self._brightness_filter = FirstOrderFilter(BACKLIGHT_OFFROAD, 10.00, 1 / gui_app.target_fps) self._brightness_thread: threading.Thread | None = None + self._brightness_event = threading.Event() + self._brightness_target: int = 0 @property def awake(self) -> bool: @@ -234,6 +261,8 @@ class Device(DeviceSP): self._interactive_timeout_callbacks.append(callback) def update(self): + self._start_brightness_thread() # start thread after manager forks ui + # do initial reset if self._interaction_time <= 0: self._reset_interactive_timeout() @@ -241,6 +270,18 @@ class Device(DeviceSP): self._update_brightness() self._update_wakefulness() + def _start_brightness_thread(self): + if self._brightness_thread is None or not self._brightness_thread.is_alive(): + self._brightness_thread = threading.Thread(target=self._brightness_worker, daemon=True) + self._brightness_thread.start() + + def _brightness_worker(self): + drop_realtime() + while True: + self._brightness_event.wait() + self._brightness_event.clear() + HARDWARE.set_screen_brightness(self._brightness_target) + def set_offroad_brightness(self, brightness: int | None): if brightness is None: brightness = BACKLIGHT_OFFROAD @@ -273,10 +314,9 @@ class Device(DeviceSP): brightness = 0 if brightness != self._last_brightness: - if self._brightness_thread is None or not self._brightness_thread.is_alive(): - self._brightness_thread = threading.Thread(target=HARDWARE.set_screen_brightness, args=(brightness,)) - self._brightness_thread.start() - self._last_brightness = brightness + self._brightness_target = brightness + self._brightness_event.set() + self._last_brightness = brightness def _update_wakefulness(self): # Handle interactive timeout diff --git a/selfdrive/ui/widgets/ssh_key.py b/selfdrive/ui/widgets/ssh_key.py index b3ff5c1711..aa7cb91b1f 100644 --- a/selfdrive/ui/widgets/ssh_key.py +++ b/selfdrive/ui/widgets/ssh_key.py @@ -59,8 +59,8 @@ class SshKeyFetcher: if not keys: raise requests.exceptions.HTTPError("No SSH keys found") - self._params.put("GithubUsername", username) - self._params.put("GithubSshKeys", keys) + self._params.put("GithubUsername", username, block=True) + self._params.put("GithubSshKeys", keys, block=True) except requests.exceptions.Timeout: self._error = tr("Request timed out") except Exception: diff --git a/sunnypilot/__init__.py b/sunnypilot/__init__.py index ccacd0be0a..59b3600531 100644 --- a/sunnypilot/__init__.py +++ b/sunnypilot/__init__.py @@ -34,6 +34,6 @@ def get_sanitize_int_param(key: str, min_val: int, max_val: int, params) -> int: clipped_val = max(min_val, min(max_val, val)) if clipped_val != val: - params.put(key, clipped_val) + params.put(key, clipped_val, block=True) return clipped_val diff --git a/sunnypilot/livedelay/lagd_toggle.py b/sunnypilot/livedelay/lagd_toggle.py index 8495dcee0a..279aa353a3 100644 --- a/sunnypilot/livedelay/lagd_toggle.py +++ b/sunnypilot/livedelay/lagd_toggle.py @@ -30,9 +30,9 @@ class LagdToggle: steer_actuator_delay = self.CP.steerActuatorDelay delay = self.software_delay self.lag = (steer_actuator_delay + delay) - self.params.put_nonblocking("LagdValueCache", self.lag) + self.params.put("LagdValueCache", self.lag) return lateral_delay = lag_msg.liveDelay.lateralDelay self.lag = lateral_delay - self.params.put_nonblocking("LagdValueCache", self.lag) + self.params.put("LagdValueCache", self.lag) diff --git a/sunnypilot/mads/helpers.py b/sunnypilot/mads/helpers.py index f9c4057bab..b9efd620f3 100644 --- a/sunnypilot/mads/helpers.py +++ b/sunnypilot/mads/helpers.py @@ -65,8 +65,8 @@ def set_car_specific_params(CP: structs.CarParams, CP_SP: structs.CarParamsSP, p # TODO-SP: To enable MADS full support for Rivian and most Tesla, identify consistent signals for MADS toggling mads_partial_support = get_mads_limited_brands(CP, CP_SP) if mads_partial_support: - params.put("MadsSteeringMode", 2) - params.put_bool("MadsUnifiedEngagementMode", True) + params.put("MadsSteeringMode", 2, block=True) + params.put_bool("MadsUnifiedEngagementMode", True, block=True) # no ACC MAIN button for these brands if CP.brand in MADS_NO_ACC_MAIN_BUTTON: diff --git a/sunnypilot/mapd/live_map_data/osm_map_data.py b/sunnypilot/mapd/live_map_data/osm_map_data.py index 0662e2d589..e2a4ec667f 100644 --- a/sunnypilot/mapd/live_map_data/osm_map_data.py +++ b/sunnypilot/mapd/live_map_data/osm_map_data.py @@ -38,7 +38,7 @@ class OsmMapData(BaseMapData): if self.last_bearing is not None: params['bearing'] = self.last_bearing - self.mem_params.put("LastGPSPosition", json.dumps(params)) + self.mem_params.put("LastGPSPosition", json.dumps(params), block=True) def get_current_speed_limit(self) -> float: return float(self.mem_params.get("MapSpeedLimit") or 0.0) diff --git a/sunnypilot/mapd/mapd_installer.py b/sunnypilot/mapd/mapd_installer.py index 08d17376d6..0e287ed405 100755 --- a/sunnypilot/mapd/mapd_installer.py +++ b/sunnypilot/mapd/mapd_installer.py @@ -30,7 +30,7 @@ def update_installed_version(version: str, params: Params = None) -> None: if params is None: params = Params() - params.put("MapdVersion", version) + params.put("MapdVersion", version, block=True) class MapdInstallManager: diff --git a/sunnypilot/mapd/mapd_manager.py b/sunnypilot/mapd/mapd_manager.py index 9de7dee8b9..88ee564190 100755 --- a/sunnypilot/mapd/mapd_manager.py +++ b/sunnypilot/mapd/mapd_manager.py @@ -56,8 +56,8 @@ def cleanup_old_osm_data(files_to_remove: list[str]) -> None: def request_refresh_osm_location_data(nations: list[str], states: list[str] | None = None) -> None: - params.put("OsmDownloadedDate", str(datetime.now().timestamp())) - params.put_bool("OsmDbUpdatesCheck", False) + params.put("OsmDownloadedDate", str(datetime.now().timestamp()), block=True) + params.put_bool("OsmDbUpdatesCheck", False, block=True) osm_download_locations = { "nations": nations, @@ -65,7 +65,7 @@ def request_refresh_osm_location_data(nations: list[str], states: list[str] | No } print(f"Downloading maps for {json.dumps(osm_download_locations)}") - mem_params.put("OSMDownloadLocations", osm_download_locations) + mem_params.put("OSMDownloadLocations", osm_download_locations, block=True) def filter_nations_and_states(nations: list[str], states: list[str] | None = None) -> tuple[list[str], list[str]]: @@ -106,10 +106,10 @@ def update_osm_db() -> None: request_refresh_osm_location_data(filtered_nations, filtered_states) if not mem_params.get("OSMDownloadBounds"): - mem_params.put("OSMDownloadBounds", "") + mem_params.put("OSMDownloadBounds", "", block=True) if not mem_params.get("LastGPSPosition"): - mem_params.put("LastGPSPosition", "{}") + mem_params.put("LastGPSPosition", "{}", block=True) def main_thread(): diff --git a/sunnypilot/models/default_model.py b/sunnypilot/models/default_model.py index f0469a4601..1d1064863f 100755 --- a/sunnypilot/models/default_model.py +++ b/sunnypilot/models/default_model.py @@ -9,7 +9,7 @@ from openpilot.sunnypilot.models.model_name import DEFAULT_MODEL DEFAULT_MODEL_NAME_PATH = os.path.join(BASEDIR, "sunnypilot", "models", "model_name.py") MODEL_HASH_PATH = os.path.join(BASEDIR, "sunnypilot", "models", "tests", "model_hash") VISION_ONNX_PATH = os.path.join(BASEDIR, "selfdrive", "modeld", "models", "driving_vision.onnx") -POLICY_ONNX_PATH = os.path.join(BASEDIR, "selfdrive", "modeld", "models", "driving_policy.onnx") +POLICY_ONNX_PATH = os.path.join(BASEDIR, "selfdrive", "modeld", "models", "driving_on_policy.onnx") def update_model_hash(): diff --git a/sunnypilot/selfdrive/car/cruise_helpers.py b/sunnypilot/selfdrive/car/cruise_helpers.py index 1c0026e12f..263d6f58cd 100644 --- a/sunnypilot/selfdrive/car/cruise_helpers.py +++ b/sunnypilot/selfdrive/car/cruise_helpers.py @@ -45,6 +45,6 @@ class CruiseHelper: def update_experimental_mode(self, events, experimental_mode) -> None: if self.button_frame_counts[ButtonType.gapAdjustCruise] >= DISTANCE_LONG_PRESS and not self.experimental_mode_switched: self._experimental_mode = not experimental_mode - self.params.put_bool_nonblocking("ExperimentalMode", self._experimental_mode) + self.params.put_bool("ExperimentalMode", self._experimental_mode) events.add(EventNameSP.experimentalModeSwitched) self.experimental_mode_switched = True diff --git a/sunnypilot/selfdrive/car/interfaces.py b/sunnypilot/selfdrive/car/interfaces.py index e4db6c8e97..5be227c262 100644 --- a/sunnypilot/selfdrive/car/interfaces.py +++ b/sunnypilot/selfdrive/car/interfaces.py @@ -93,17 +93,14 @@ def _cleanup_unsupported_params(CP: structs.CarParams, CP_SP: structs.CarParamsS def setup_interfaces(CI: CarInterfaceBase, params: Params = None) -> None: - CP = CI.CP - CP_SP = CI.CP_SP - - enforce_torque = _enforce_torque_lateral_control(CP, params) - nnlc_enabled = _initialize_neural_network_lateral_control(CP, CP_SP, params) - _initialize_intelligent_cruise_button_management(CP, CP_SP, params) - _initialize_torque_lateral_control(CI, CP, enforce_torque, nnlc_enabled) - _cleanup_unsupported_params(CP, CP_SP) + enforce_torque = _enforce_torque_lateral_control(CI.CP, params) + nnlc_enabled = _initialize_neural_network_lateral_control(CI.CP, CI.CP_SP, params) + _initialize_intelligent_cruise_button_management(CI.CP, CI.CP_SP, params) + _initialize_torque_lateral_control(CI, CI.CP, enforce_torque, nnlc_enabled) + _cleanup_unsupported_params(CI.CP, CI.CP_SP) try: - STATSLOGSP.raw('sunnypilot.car_params', CP.to_dict()) + STATSLOGSP.raw('sunnypilot.car_params', CI.CP.to_dict()) except RuntimeError: pass # to_dict fails on macOS due to library issues. # STATSLOGSP.raw('sunnypilot_params.car_params_sp', CP_SP.to_dict()) # https://github.com/sunnypilot/opendbc/pull/361 diff --git a/sunnypilot/selfdrive/car/sync_sunnylink_params.py b/sunnypilot/selfdrive/car/sync_sunnylink_params.py index 5e25f6da9a..7539e741c6 100755 --- a/sunnypilot/selfdrive/car/sync_sunnylink_params.py +++ b/sunnypilot/selfdrive/car/sync_sunnylink_params.py @@ -21,7 +21,7 @@ def update_car_list_param(): params = Params() if params.get("CarList") != current_car_list: - params.put("CarList", current_car_list) + params.put("CarList", current_car_list, block=True) cloudlog.warning("Updated CarList param with latest platform list") else: cloudlog.warning("CarList param is up to date, no need to update") diff --git a/sunnypilot/selfdrive/car/tests/test_custom_cruise.py b/sunnypilot/selfdrive/car/tests/test_custom_cruise.py index 7276af43e7..878bc78b03 100644 --- a/sunnypilot/selfdrive/car/tests/test_custom_cruise.py +++ b/sunnypilot/selfdrive/car/tests/test_custom_cruise.py @@ -21,9 +21,9 @@ class TestCustomAccIncrements(TestVCruiseHelper): def reset_custom_params(self) -> None: """Reset to default custom ACC parameters""" - self.params.put_bool("CustomAccIncrementsEnabled", False) - self.params.put("CustomAccShortPressIncrement", 1) - self.params.put("CustomAccLongPressIncrement", 5) + self.params.put_bool("CustomAccIncrementsEnabled", False, block=True) + self.params.put("CustomAccShortPressIncrement", 1, block=True) + self.params.put("CustomAccLongPressIncrement", 5, block=True) self.v_cruise_helper.read_custom_set_speed_params() def press_button_short(self, button_type: car.CarState.ButtonEvent.Type) -> None: @@ -51,9 +51,9 @@ class TestCustomAccIncrements(TestVCruiseHelper): def set_custom_increments(self, enabled: bool, short_inc: int, long_inc: int) -> None: """Set custom ACC increment parameters""" - self.params.put_bool("CustomAccIncrementsEnabled", enabled) - self.params.put("CustomAccShortPressIncrement", short_inc) - self.params.put("CustomAccLongPressIncrement", long_inc) + self.params.put_bool("CustomAccIncrementsEnabled", enabled, block=True) + self.params.put("CustomAccShortPressIncrement", short_inc, block=True) + self.params.put("CustomAccLongPressIncrement", long_inc, block=True) self.v_cruise_helper.read_custom_set_speed_params() def test_default_behavior_when_disabled(self): diff --git a/sunnypilot/selfdrive/controls/controlsd_ext.py b/sunnypilot/selfdrive/controls/controlsd_ext.py index dfda5549f2..c8d054243f 100644 --- a/sunnypilot/selfdrive/controls/controlsd_ext.py +++ b/sunnypilot/selfdrive/controls/controlsd_ext.py @@ -68,35 +68,41 @@ class ControlsExt(ModelStateBase): return bool(sm['selfdriveState'].active) @staticmethod - def get_lead_data(ld: log.RadarState.LeadData) -> dict: - return { - "dRel": ld.dRel, - "yRel": ld.yRel, - "vRel": ld.vRel, - "aRel": ld.aRel, - "vLead": ld.vLead, - "dPath": ld.dPath, - "vLat": ld.vLat, - "vLeadK": ld.vLeadK, - "aLeadK": ld.aLeadK, - "fcw": ld.fcw, - "status": ld.status, - "aLeadTau": ld.aLeadTau, - "modelProb": ld.modelProb, - "radar": ld.radar, - "radarTrackId": ld.radarTrackId, - } + def get_lead_data(_lead, src: log.RadarState.LeadData) -> None: + _lead.dRel = src.dRel + _lead.yRel = src.yRel + _lead.vRel = src.vRel + _lead.aRel = src.aRel + _lead.vLead = src.vLead + _lead.dPath = src.dPath + _lead.vLat = src.vLat + _lead.vLeadK = src.vLeadK + _lead.aLeadK = src.aLeadK + _lead.fcw = src.fcw + _lead.status = src.status + _lead.aLeadTau = src.aLeadTau + _lead.modelProb = src.modelProb + _lead.radar = src.radar + _lead.radarTrackId = src.radarTrackId def state_control_ext(self, sm: messaging.SubMaster) -> custom.CarControlSP: CC_SP = custom.CarControlSP.new_message() - CC_SP.leadOne = self.get_lead_data(sm['radarState'].leadOne) - CC_SP.leadTwo = self.get_lead_data(sm['radarState'].leadTwo) + self.get_lead_data(CC_SP.leadOne, sm['radarState'].leadOne) + self.get_lead_data(CC_SP.leadTwo, sm['radarState'].leadTwo) # MADS state - CC_SP.mads = sm['selfdriveStateSP'].mads + mads_src = sm['selfdriveStateSP'].mads + CC_SP.mads.state = mads_src.state + CC_SP.mads.enabled = mads_src.enabled + CC_SP.mads.active = mads_src.active + CC_SP.mads.available = mads_src.available - CC_SP.intelligentCruiseButtonManagement = sm['selfdriveStateSP'].intelligentCruiseButtonManagement + # ICBM state + icbm_src = sm['selfdriveStateSP'].intelligentCruiseButtonManagement + CC_SP.intelligentCruiseButtonManagement.state = icbm_src.state + CC_SP.intelligentCruiseButtonManagement.sendButton = icbm_src.sendButton + CC_SP.intelligentCruiseButtonManagement.vTarget = icbm_src.vTarget return CC_SP diff --git a/sunnypilot/selfdrive/controls/lib/nnlc/tests/test_load_model.py b/sunnypilot/selfdrive/controls/lib/nnlc/tests/test_load_model.py index 3594588ea2..2f4e0d6993 100644 --- a/sunnypilot/selfdrive/controls/lib/nnlc/tests/test_load_model.py +++ b/sunnypilot/selfdrive/controls/lib/nnlc/tests/test_load_model.py @@ -15,7 +15,7 @@ class TestNNTorqueModel: @parameterized.expand([HONDA.HONDA_CIVIC, TOYOTA.TOYOTA_RAV4, HYUNDAI.HYUNDAI_SANTA_CRUZ_1ST_GEN]) def test_load_model(self, car_name): params = Params() - params.put_bool("NeuralNetworkLateralControl", True) + params.put_bool("NeuralNetworkLateralControl", True, block=True) CarInterface = interfaces[car_name] CP = CarInterface.get_non_essential_params(car_name) diff --git a/sunnypilot/selfdrive/controls/lib/nnlc/tests/test_nnlc.py b/sunnypilot/selfdrive/controls/lib/nnlc/tests/test_nnlc.py index a108e4ce29..f2009926cf 100644 --- a/sunnypilot/selfdrive/controls/lib/nnlc/tests/test_nnlc.py +++ b/sunnypilot/selfdrive/controls/lib/nnlc/tests/test_nnlc.py @@ -46,7 +46,7 @@ class TestNeuralNetworkLateralControl: @parameterized.expand([HONDA.HONDA_CIVIC, TOYOTA.TOYOTA_RAV4, HYUNDAI.HYUNDAI_SANTA_CRUZ_1ST_GEN, GM.CHEVROLET_BOLT_EUV]) def test_saturation(self, car_name): params = Params() - params.put_bool("NeuralNetworkLateralControl", True) + params.put_bool("NeuralNetworkLateralControl", True, block=True) CarInterface = interfaces[car_name] CP = CarInterface.get_non_essential_params(car_name) diff --git a/sunnypilot/selfdrive/controls/lib/smart_cruise_control/tests/test_map_controller.py b/sunnypilot/selfdrive/controls/lib/smart_cruise_control/tests/test_map_controller.py index 537f0033f0..254e85f573 100644 --- a/sunnypilot/selfdrive/controls/lib/smart_cruise_control/tests/test_map_controller.py +++ b/sunnypilot/selfdrive/controls/lib/smart_cruise_control/tests/test_map_controller.py @@ -24,11 +24,11 @@ class TestSmartCruiseControlMap: self.scc_m = SmartCruiseControlMap() def reset_params(self): - self.params.put_bool("SmartCruiseControlMap", True) + self.params.put_bool("SmartCruiseControlMap", True, block=True) # TODO-SP: mock data from gpsLocation - self.params.put("LastGPSPosition", "{}") - self.params.put("MapTargetVelocities", "{}") + self.params.put("LastGPSPosition", "{}", block=True) + self.params.put("MapTargetVelocities", "{}", block=True) def test_initial_state(self): assert self.scc_m.state == VisionState.disabled @@ -37,7 +37,7 @@ class TestSmartCruiseControlMap: assert self.scc_m.output_a_target == 0. def test_system_disabled(self): - self.params.put_bool("SmartCruiseControlMap", False) + self.params.put_bool("SmartCruiseControlMap", False, block=True) self.scc_m.enabled = self.params.get_bool("SmartCruiseControlMap") for _ in range(int(10. / DT_MDL)): diff --git a/sunnypilot/selfdrive/controls/lib/smart_cruise_control/tests/test_vision_controller.py b/sunnypilot/selfdrive/controls/lib/smart_cruise_control/tests/test_vision_controller.py index d35b79a73b..2a2c6a6be1 100644 --- a/sunnypilot/selfdrive/controls/lib/smart_cruise_control/tests/test_vision_controller.py +++ b/sunnypilot/selfdrive/controls/lib/smart_cruise_control/tests/test_vision_controller.py @@ -116,7 +116,7 @@ class TestSmartCruiseControlVision: self.sm = {'modelV2': mdl.modelV2, 'carState': cs.carState, 'controlsState': controls_state.controlsState} def reset_params(self): - self.params.put_bool("SmartCruiseControlVision", True) + self.params.put_bool("SmartCruiseControlVision", True, block=True) def test_initial_state(self): assert self.scc_v.state == VisionState.disabled @@ -125,7 +125,7 @@ class TestSmartCruiseControlVision: assert self.scc_v.output_a_target == 0. def test_system_disabled(self): - self.params.put_bool("SmartCruiseControlVision", False) + self.params.put_bool("SmartCruiseControlVision", False, block=True) self.scc_v.enabled = self.params.get_bool("SmartCruiseControlVision") for _ in range(int(10. / DT_MDL)): diff --git a/sunnypilot/selfdrive/controls/lib/speed_limit/helpers.py b/sunnypilot/selfdrive/controls/lib/speed_limit/helpers.py index 4f388befc7..9eddceb820 100644 --- a/sunnypilot/selfdrive/controls/lib/speed_limit/helpers.py +++ b/sunnypilot/selfdrive/controls/lib/speed_limit/helpers.py @@ -39,6 +39,6 @@ def set_speed_limit_assist_availability(CP: car.CarParams, CP_SP: custom.CarPara if not allowed: if params.get("SpeedLimitMode", return_default=True) == SpeedLimitMode.assist: - params.put("SpeedLimitMode", int(SpeedLimitMode.warning)) + params.put("SpeedLimitMode", int(SpeedLimitMode.warning), block=True) return allowed diff --git a/sunnypilot/selfdrive/controls/lib/speed_limit/tests/test_speed_limit_assist.py b/sunnypilot/selfdrive/controls/lib/speed_limit/tests/test_speed_limit_assist.py index f857966a73..6dbe32eaf4 100644 --- a/sunnypilot/selfdrive/controls/lib/speed_limit/tests/test_speed_limit_assist.py +++ b/sunnypilot/selfdrive/controls/lib/speed_limit/tests/test_speed_limit_assist.py @@ -75,11 +75,11 @@ class TestSpeedLimitAssist: return CI def reset_custom_params(self): - self.params.put("IsReleaseSpBranch", True) - self.params.put("SpeedLimitMode", int(Mode.assist)) - self.params.put_bool("IsMetric", False) - self.params.put("SpeedLimitOffsetType", 0) - self.params.put("SpeedLimitValueOffset", 0) + self.params.put("IsReleaseSpBranch", True, block=True) + self.params.put("SpeedLimitMode", int(Mode.assist), block=True) + self.params.put_bool("IsMetric", False, block=True) + self.params.put("SpeedLimitOffsetType", 0, block=True) + self.params.put("SpeedLimitValueOffset", 0, block=True) def reset_state(self): self.sla.state = SpeedLimitAssistState.disabled @@ -115,14 +115,14 @@ class TestSpeedLimitAssist: assert not self.sla.enabled # stay disallowed even when the param may have changed from somewhere else - self.params.put("SpeedLimitMode", int(Mode.assist)) + self.params.put("SpeedLimitMode", int(Mode.assist), block=True) for _ in range(int(PARAMS_UPDATE_PERIOD / DT_MDL)): self.sla.update(True, False, SPEED_LIMITS['city'], 0, SPEED_LIMITS['highway'], SPEED_LIMITS['city'], SPEED_LIMITS['city'], True, 0, self.events_sp) assert not self.sla.enabled def test_disabled(self): - self.params.put("SpeedLimitMode", int(Mode.off)) + self.params.put("SpeedLimitMode", int(Mode.off), block=True) for _ in range(int(10. / DT_MDL)): self.sla.update(True, False, SPEED_LIMITS['city'], 0, SPEED_LIMITS['highway'], SPEED_LIMITS['city'], SPEED_LIMITS['city'], True, 0, self.events_sp) assert self.sla.state == SpeedLimitAssistState.disabled diff --git a/sunnypilot/selfdrive/locationd/locationd.cc b/sunnypilot/selfdrive/locationd/locationd.cc index c42ab13f25..b24daa961b 100644 --- a/sunnypilot/selfdrive/locationd/locationd.cc +++ b/sunnypilot/selfdrive/locationd/locationd.cc @@ -255,7 +255,7 @@ void Localizer::handle_sensor(double current_time, const cereal::SensorEventData } // Gyro Uncalibrated - if (log.getSensor() == SENSOR_GYRO_UNCALIBRATED && log.getType() == SENSOR_TYPE_GYROSCOPE_UNCALIBRATED) { + if (log.which() == cereal::SensorEventData::GYRO_UNCALIBRATED) { auto v = log.getGyroUncalibrated().getV(); auto meas = Vector3d(-v[2], -v[1], -v[0]); @@ -273,7 +273,7 @@ void Localizer::handle_sensor(double current_time, const cereal::SensorEventData } // Accelerometer - if (log.getSensor() == SENSOR_ACCELEROMETER && log.getType() == SENSOR_TYPE_ACCELEROMETER) { + if (log.which() == cereal::SensorEventData::ACCELERATION) { auto v = log.getAcceleration().getV(); // TODO: reduce false positives and re-enable this check diff --git a/sunnypilot/selfdrive/locationd/tests/test_locationd.py b/sunnypilot/selfdrive/locationd/tests/test_locationd.py index 877bc821da..1f5bfd3b25 100644 --- a/sunnypilot/selfdrive/locationd/tests/test_locationd.py +++ b/sunnypilot/selfdrive/locationd/tests/test_locationd.py @@ -19,7 +19,7 @@ if platform.system() == 'Darwin': class TestLocationdProc: LLD_MSGS = ['gpsLocationExternal', 'cameraOdometry', 'carState', 'liveCalibration', - 'accelerometer', 'gyroscope', 'magnetometer'] + 'accelerometer', 'gyroscope'] def setup_method(self): self.pm = messaging.PubMaster(self.LLD_MSGS) diff --git a/sunnypilot/selfdrive/selfdrived/events.py b/sunnypilot/selfdrive/selfdrived/events.py index b1343b2a08..27b44fb4fc 100644 --- a/sunnypilot/selfdrive/selfdrived/events.py +++ b/sunnypilot/selfdrive/selfdrived/events.py @@ -40,7 +40,7 @@ def speed_limit_adjust_alert(CP: car.CarParams, CS: car.CarState, sm: messaging. def speed_limit_pre_active_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: speed_conv = CV.MS_TO_KPH if metric else CV.MS_TO_MPH v_cruise_cluster = CS.vCruiseCluster - set_speed = sm['controlsState'].vCruiseDEPRECATED if v_cruise_cluster == 0.0 else v_cruise_cluster + set_speed = sm['controlsState'].deprecated.vCruise if v_cruise_cluster == 0.0 else v_cruise_cluster set_speed_conv = round(set_speed * speed_conv) speed_limit_final_last = sm['longitudinalPlanSP'].speedLimit.resolver.speedLimitFinalLast diff --git a/sunnypilot/sunnylink/api.py b/sunnypilot/sunnylink/api.py index 5260f6bd9d..a881faca04 100644 --- a/sunnypilot/sunnylink/api.py +++ b/sunnypilot/sunnylink/api.py @@ -85,7 +85,7 @@ class SunnylinkApi(BaseApi): sunnylink_dongle_id = UNREGISTERED_SUNNYLINK_DONGLE_ID self._status_update("Public key not found, setting dongle ID to unregistered.") else: - Params().put("LastSunnylinkPingTime", 0) # Reset the last ping time to 0 if we are trying to register + Params().put("LastSunnylinkPingTime", 0, block=True) # Reset the last ping time to 0 if we are trying to register backoff = 1 while True: @@ -137,15 +137,15 @@ class SunnylinkApi(BaseApi): time.sleep(3) break - self.params.put("SunnylinkDongleId", sunnylink_dongle_id or UNREGISTERED_SUNNYLINK_DONGLE_ID) + self.params.put("SunnylinkDongleId", sunnylink_dongle_id or UNREGISTERED_SUNNYLINK_DONGLE_ID, block=True) # Set the last ping time to the current time since we were just talking to the API last_ping = int((time.monotonic() if successful_registration else start_time) * 1e9) - Params().put("LastSunnylinkPingTime", last_ping) + Params().put("LastSunnylinkPingTime", last_ping, block=True) # Disable sunnylink if registration was not successful if not successful_registration: - Params().put_bool("SunnylinkEnabled", False) + Params().put_bool("SunnylinkEnabled", False, block=True) self.spinner = None return sunnylink_dongle_id diff --git a/sunnypilot/sunnylink/athena/sunnylinkd.py b/sunnypilot/sunnylink/athena/sunnylinkd.py index 5e7b400d97..ce622bc5ad 100755 --- a/sunnypilot/sunnylink/athena/sunnylinkd.py +++ b/sunnypilot/sunnylink/athena/sunnylinkd.py @@ -126,7 +126,7 @@ def ws_recv(ws: WebSocket, end_event: threading.Event) -> None: elif opcode in (ABNF.OPCODE_PING, ABNF.OPCODE_PONG): cloudlog.debug("sunnylinkd.ws_recv.pong") last_ping = int(time.monotonic() * 1e9) - Params().put("LastSunnylinkPingTime", last_ping) + Params().put("LastSunnylinkPingTime", last_ping, block=True) except WebSocketTimeoutException: ns_since_last_ping = int(time.monotonic() * 1e9) - last_ping if ns_since_last_ping > SUNNYLINK_RECONNECT_TIMEOUT_S * 1e9: @@ -281,7 +281,7 @@ def saveParams(params_to_update: dict[str, str], compression: bool = False) -> N # Increment version counter for frontend change detection try: current = int(params.get("ParamsVersion") or "0") - params.put("ParamsVersion", str(current + 1)) + params.put("ParamsVersion", str(current + 1), block=True) except Exception: pass diff --git a/sunnypilot/sunnylink/params_metadata.json b/sunnypilot/sunnylink/params_metadata.json index 83a0cec94a..764f37ffde 100644 --- a/sunnypilot/sunnylink/params_metadata.json +++ b/sunnypilot/sunnylink/params_metadata.json @@ -620,6 +620,10 @@ "title": "Self-Tune", "description": "Enables self-tune for Torque lateral control" }, + "LivestreamEncoderBitrate": { + "title": "Livestream Encoder Bitrate", + "description": "" + }, "LocationFilterInitialState": { "title": "Location Filter Initial State", "description": "" @@ -1392,6 +1396,14 @@ "title": "Uptime Onroad", "description": "" }, + "UsbGpuCompiled": { + "title": "Usb Gpu Compiled", + "description": "" + }, + "UsbGpuPresent": { + "title": "Usb Gpu Present", + "description": "" + }, "Version": { "title": "openpilot Version", "description": "" diff --git a/sunnypilot/sunnylink/registration_manager.py b/sunnypilot/sunnylink/registration_manager.py index 1b822e5c2d..3e00c5c013 100755 --- a/sunnypilot/sunnylink/registration_manager.py +++ b/sunnypilot/sunnylink/registration_manager.py @@ -27,7 +27,7 @@ def main(): register_sunnylink() except Exception: cloudlog.exception("Sunnylink registration failed") - Params().put_bool("SunnylinkTempFault", True) + Params().put_bool("SunnylinkTempFault", True, block=True) raise diff --git a/sunnypilot/sunnylink/sunnylink_state.py b/sunnypilot/sunnylink/sunnylink_state.py index 927d041991..a4a3df3a2b 100644 --- a/sunnypilot/sunnylink/sunnylink_state.py +++ b/sunnypilot/sunnylink/sunnylink_state.py @@ -141,7 +141,7 @@ class SunnylinkState: response = self._api.api_get(f"device/{self.sunnylink_dongle_id}/roles", method='GET', access_token=token, session=self._session) if response.status_code == 200: roles = response.text - self._params.put("SunnylinkCache_Roles", roles) + self._params.put("SunnylinkCache_Roles", roles, block=True) with self._lock: self._roles = _parse_roles(roles) sponsor_tier = self._get_highest_tier() @@ -160,7 +160,7 @@ class SunnylinkState: response = self._api.api_get(f"device/{self.sunnylink_dongle_id}/users", method='GET', access_token=token, session=self._session) if response.status_code == 200: users = response.text - self._params.put("SunnylinkCache_Users", users) + self._params.put("SunnylinkCache_Users", users, block=True) with self._lock: self._users = _parse_users(users) except Exception as e: diff --git a/sunnypilot/sunnylink/utils.py b/sunnypilot/sunnylink/utils.py index f4f14f7e81..89c3c8a0c8 100644 --- a/sunnypilot/sunnylink/utils.py +++ b/sunnypilot/sunnylink/utils.py @@ -52,7 +52,7 @@ def register_sunnylink(): sunnylink_id = SunnylinkApi(None).register_device(None, **extra_args) print(f"SunnyLinkId: {sunnylink_id}") except Exception: - Params().put_bool("SunnylinkTempFault", True) + Params().put_bool("SunnylinkTempFault", True, block=True) raise @@ -98,7 +98,7 @@ def save_param_from_base64_encoded_string(param_name: str, base64_encoded_data: # We convert to string anything that isn't bytes first. We later transform further. param_value = _convert_param_to_type(value, param_type) - params.put(param_name, param_value) + params.put(param_name, param_value, block=True) def _convert_param_to_type(value: bytes, param_type: ParamKeyType) -> bytes | str | int | float | bool | dict | None: diff --git a/sunnypilot/system/params_migration.py b/sunnypilot/system/params_migration.py index 2f796c174e..f9d7d1bc43 100644 --- a/sunnypilot/system/params_migration.py +++ b/sunnypilot/system/params_migration.py @@ -43,7 +43,7 @@ def _migrate_car_platform_bundle(_params): else: bundle["platform"] = new_platform - _params.put("CarPlatformBundle", bundle) + _params.put("CarPlatformBundle", bundle, block=True) cloudlog.info(f"params_migration: CarPlatformBundle migrated {old_platform!r} -> {new_platform!r}") @@ -54,12 +54,12 @@ def run_migration(_params): val = _params.get("OnroadScreenOffBrightness", return_default=True) if val >= 2: # old: 5%, new: Screen Off new_val = val + 1 - _params.put("OnroadScreenOffBrightness", new_val) + _params.put("OnroadScreenOffBrightness", new_val, block=True) log_str = f"Successfully migrated OnroadScreenOffBrightness from {val} to {new_val}." else: log_str = "Migration not required for OnroadScreenOffBrightness." - _params.put("OnroadScreenOffBrightnessMigrated", ONROAD_BRIGHTNESS_MIGRATION_VERSION) + _params.put("OnroadScreenOffBrightnessMigrated", ONROAD_BRIGHTNESS_MIGRATION_VERSION, block=True) cloudlog.info(log_str + f" Setting OnroadScreenOffBrightnessMigrated to {ONROAD_BRIGHTNESS_MIGRATION_VERSION}") except Exception as e: cloudlog.exception(f"Error migrating OnroadScreenOffBrightness: {e}") @@ -69,12 +69,12 @@ def run_migration(_params): try: val = _params.get("OnroadScreenOffTimer", return_default=True) if val not in VALID_TIMER_VALUES: - _params.put("OnroadScreenOffTimer", 15) + _params.put("OnroadScreenOffTimer", 15, block=True) log_str = f"Successfully migrated OnroadScreenOffTimer from {val} to 15 (default)." else: log_str = "Migration not required for OnroadScreenOffTimer." - _params.put("OnroadScreenOffTimerMigrated", ONROAD_BRIGHTNESS_TIMER_MIGRATION_VERSION) + _params.put("OnroadScreenOffTimerMigrated", ONROAD_BRIGHTNESS_TIMER_MIGRATION_VERSION, block=True) cloudlog.info(log_str + f" Setting OnroadScreenOffTimerMigrated to {ONROAD_BRIGHTNESS_TIMER_MIGRATION_VERSION}") except Exception as e: cloudlog.exception(f"Error migrating OnroadScreenOffTimer: {e}") diff --git a/sunnypilot/system/updated/tests/test_sp_branch_migrations.py b/sunnypilot/system/updated/tests/test_sp_branch_migrations.py index 661fa19840..b2742841a0 100644 --- a/sunnypilot/system/updated/tests/test_sp_branch_migrations.py +++ b/sunnypilot/system/updated/tests/test_sp_branch_migrations.py @@ -48,7 +48,7 @@ def test_sp_branch_migrations_from_current_branch(mocker, device_type, branch, e ]) def test_sp_branch_migrations_from_param(mocker, device_type, branch, expected): params = Params() - params.put("UpdaterTargetBranch", branch) + params.put("UpdaterTargetBranch", branch, block=True) mocker.patch("openpilot.system.updated.updated.HARDWARE.get_device_type", return_value=device_type) diff --git a/system/athena/athenad.py b/system/athena/athenad.py index 9773eec090..9b3262ad99 100755 --- a/system/athena/athenad.py +++ b/system/athena/athenad.py @@ -29,7 +29,7 @@ from websocket import (ABNF, WebSocket, WebSocketException, WebSocketTimeoutExce create_connection) import cereal.messaging as messaging -from cereal import log +from cereal import car, log from cereal.services import SERVICE_LIST from openpilot.common.api import Api, get_key_pair from openpilot.common.utils import CallbackReader, get_upload_stream @@ -45,6 +45,7 @@ from openpilot.system.hardware.hw import Paths ATHENA_HOST = os.getenv('ATHENA_HOST', 'wss://athena.comma.ai') HANDLER_THREADS = int(os.getenv('HANDLER_THREADS', "4")) LOCAL_PORT_WHITELIST = {22, } # SSH +WEBRTCD_PORT = 5001 LOG_ATTR_NAME = 'user.upload' LOG_ATTR_VALUE_MAX_UNIX_TIME = int.to_bytes(2147483647, 4, sys.byteorder) @@ -163,7 +164,7 @@ class UploadQueueCache: try: queue: list[UploadItem | None] = list(upload_queue.queue) items = [asdict(i) for i in queue if i is not None and (i.id not in cancelled_uploads)] - Params().put("AthenadUploadQueue", items) + Params().put("AthenadUploadQueue", items, block=True) except Exception: cloudlog.exception("athena.UploadQueueCache.cache.exception") @@ -504,7 +505,7 @@ def setRouteViewed(route: str) -> dict[str, int | str]: # remove duplicates routes = list(dict.fromkeys(routes)) - params.put("AthenadRecentlyViewedRoutes", ",".join(routes[-10:])) + params.put("AthenadRecentlyViewedRoutes", ",".join(routes[-10:]), block=True) return {"success": 1} @@ -567,6 +568,16 @@ def getSshAuthorizedKeys() -> str: def getGithubUsername() -> str: return cast(str, Params().get("GithubUsername") or "") + +@dispatcher.add_method +def getNotCar() -> bool: + cp_bytes = Params().get("CarParamsPersistent") + if cp_bytes is not None: + with car.CarParams.from_bytes(cp_bytes) as CP: + return CP.notCar + return False + + @dispatcher.add_method def getSimInfo(): return HARDWARE.get_sim_info() @@ -588,6 +599,35 @@ def getNetworks(): return HARDWARE.get_networks() +@dispatcher.add_method +def startStream(sdp: str) -> dict: + from openpilot.system.webrtc.webrtcd import StreamRequestBody + bridge_services_in = [] + + # get live car params to avoid stale notCar edge case + cp_bytes = Params().get("CarParams") + if cp_bytes is not None: + with car.CarParams.from_bytes(cp_bytes) as CP: + if CP.notCar: + bridge_services_in.append("testJoystick") + + body = StreamRequestBody(sdp, "wideRoad", bridge_services_in, ["carState"]) + try: + resp = requests.post(f"http://localhost:{WEBRTCD_PORT}/stream", + json=asdict(body), timeout=10) + if not resp.ok: + try: + error_body = resp.json() + raise Exception(error_body.get("message", f"webrtcd returned {resp.status_code}")) + except ValueError: + resp.raise_for_status() + return resp.json() + except requests.ConnectTimeout as e: + raise Exception("webrtc took too long to respond. is it on?") from e + except requests.ConnectionError as e: + raise Exception("webrtc is not running. turn on comma body ignition.") from e + + @dispatcher.add_method def takeSnapshot() -> str | dict[str, str] | None: from openpilot.system.camerad.snapshot import jpeg_write, snapshot @@ -843,7 +883,7 @@ def ws_recv(ws: WebSocket, end_event: threading.Event) -> None: recv_queue.put_nowait(data) elif opcode == ABNF.OPCODE_PING: last_ping = int(time.monotonic() * 1e9) - Params().put("LastAthenaPingTime", last_ping) + Params().put("LastAthenaPingTime", last_ping, block=True) except WebSocketTimeoutException: ns_since_last_ping = int(time.monotonic() * 1e9) - last_ping if ns_since_last_ping > RECONNECT_TIMEOUT_S * 1e9: diff --git a/system/athena/registration.py b/system/athena/registration.py index 26a2adb1af..bc7cf6c748 100755 --- a/system/athena/registration.py +++ b/system/athena/registration.py @@ -97,7 +97,7 @@ def register(show_spinner=False) -> str | None: spinner.close() if dongle_id: - params.put("DongleId", dongle_id) + params.put("DongleId", dongle_id, block=True) set_offroad_alert("Offroad_UnregisteredHardware", (dongle_id == UNREGISTERED_DONGLE_ID) and not PC) return dongle_id diff --git a/system/athena/tests/test_athenad.py b/system/athena/tests/test_athenad.py index 5b3e0b41f4..b0c20a26a9 100644 --- a/system/athena/tests/test_athenad.py +++ b/system/athena/tests/test_athenad.py @@ -73,8 +73,8 @@ class TestAthenadMethods: self.params = Params() for k, v in self.default_params.items(): - self.params.put(k, v) - self.params.put_bool("GsmMetered", True) + self.params.put(k, v, block=True) + self.params.put_bool("GsmMetered", True, block=True) athenad.upload_queue = queue.PriorityQueue() athenad.cur_upload_items.clear() diff --git a/system/athena/tests/test_registration.py b/system/athena/tests/test_registration.py index c20722659a..f5d900d4db 100644 --- a/system/athena/tests/test_registration.py +++ b/system/athena/tests/test_registration.py @@ -37,7 +37,7 @@ class TestRegistration: dongle = "DONGLE_ID_123" m = mocker.patch("openpilot.system.athena.registration.api_get", autospec=True) for persist, params in [(True, True), (True, False), (False, True)]: - self.params.put("DongleId", dongle if params else "") + self.params.put("DongleId", dongle if params else "", block=True) with open(self.dongle_id, "w") as f: f.write(dongle if persist else "") assert register() == dongle diff --git a/system/camerad/cameras/bps_blobs.h b/system/camerad/cameras/bps_blobs.h index 54941b8d76..ee31698e7f 100644 --- a/system/camerad/cameras/bps_blobs.h +++ b/system/camerad/cameras/bps_blobs.h @@ -8,23 +8,23 @@ unsigned char bps_cfg[4][768] = { +{ /* placeholder */ }, { /* placeholder */ }, {0x3, 0x0, 0x0, 0x0, 0x88, 0x7, 0x0, 0x0, 0xB8, 0x4, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x50, 0xB, 0x0, 0x0, 0xB8, 0x4, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x14, 0x0, 0x0, 0x0, 0x88, 0x7, 0x0, 0x0, 0xB8, 0x4, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x0, 0x0, 0xC0, 0x4, 0x0, 0x0, 0x0, 0x8, 0x0, 0x0, 0x60, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}, - {0x3, 0x0, 0x0, 0x0, 0x88, 0x7, 0x0, 0x0, 0xB8, 0x4, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x50, 0xB, 0x0, 0x0, 0xB8, 0x4, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x14, 0x0, 0x0, 0x0, 0x88, 0x7, 0x0, 0x0, 0xB8, 0x4, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x0, 0x0, 0xC0, 0x4, 0x0, 0x0, 0x0, 0x8, 0x0, 0x0, 0x60, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}, - {0x3, 0x0, 0x0, 0x0, 0x40, 0x5, 0x0, 0x0, 0xF8, 0x2, 0x0, 0x0, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xE0, 0x7, 0x0, 0x0, 0xF8, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x14, 0x0, 0x0, 0x0, 0x40, 0x5, 0x0, 0x0, 0xF8, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x80, 0x5, 0x0, 0x0, 0x0, 0x3, 0x0, 0x0, 0x80, 0x5, 0x0, 0x0, 0x80, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}, + {0x3, 0x0, 0x0, 0x0, 0x80, 0xA, 0x0, 0x0, 0xF0, 0x5, 0x0, 0x0, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC0, 0xF, 0x0, 0x0, 0xF0, 0x5, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x14, 0x0, 0x0, 0x0, 0x80, 0xA, 0x0, 0x0, 0xF0, 0x5, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x80, 0xA, 0x0, 0x0, 0x0, 0x6, 0x0, 0x0, 0x80, 0xA, 0x0, 0x0, 0x0, 0x3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x14, 0x0, 0x0, 0x0, 0x40, 0x5, 0x0, 0x0, 0xF8, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x80, 0x5, 0x0, 0x0, 0x0, 0x3, 0x0, 0x0, 0x80, 0x5, 0x0, 0x0, 0x80, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}, }; -unsigned char bps_striping_output[4][0x9a0] = { +unsigned char bps_striping_output[4][0xc58] = { { /* placeholder */ }, - {0x5, 0x0, 0x6, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x4, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x4, 0x0, 0x0, 0xFF, 0xFF, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x4, 0x0, 0x0, 0xB7, 0x4, 0x0, 0x0, 0xB7, 0x4, 0x0, 0x0, 0x5B, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x4, 0x0, 0x0, 0x5B, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x4, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xB8, 0x4, 0x5C, 0x2, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x5, 0x0, 0x0, 0x0, 0x70, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC0, 0x89, 0x23, 0x0, 0x1, 0x0, 0x0, 0x0, 0xCC, 0x5, 0x87, 0x7, 0x0, 0x0, 0x0, 0x0, 0xD0, 0x5, 0x87, 0x7, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0xB, 0x0, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xB8, 0x1, 0xDC, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x2, 0xA4, 0xFD, 0x50, 0xB1, 0x9, 0x0, 0x8, 0x0, 0x33, 0x0, 0x8, 0x2, 0xA4, 0xFD, 0x50, 0xB1, 0x9, 0x0, 0x8, 0x0, 0x33, 0x0, 0x0, 0x0, 0x0, 0x0, 0x6, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xE, 0x2, 0xA6, 0xFD, 0x68, 0xC0, 0x9, 0x0, 0x8, 0x0, 0x34, 0x0, 0xD0, 0x5, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x1C, 0x8, 0x0, 0x14, 0x4, 0xD3, 0x5, 0x0, 0x0, 0x0, 0x0, 0x18, 0x4, 0xCF, 0x5, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0xB, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xB8, 0x1, 0xDC, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x50, 0x0, 0xA4, 0xFD, 0x10, 0xAA, 0x5, 0x0, 0x8, 0x0, 0x33, 0x0, 0x50, 0x0, 0xA4, 0xFD, 0x10, 0xAA, 0x5, 0x0, 0x8, 0x0, 0x33, 0x0, 0x0, 0x0, 0x0, 0x0, 0xA, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x56, 0x0, 0xA6, 0xFD, 0x88, 0xA4, 0x5, 0x0, 0x8, 0x0, 0x34, 0x0, 0x18, 0x4, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x1C, 0x8, 0x0, 0x5C, 0x2, 0x1B, 0x4, 0x0, 0x0, 0x0, 0x0, 0x60, 0x2, 0x17, 0x4, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0xB, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xB8, 0x1, 0xDC, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x98, 0xFE, 0xA4, 0xFD, 0x50, 0x8B, 0x7, 0x0, 0x8, 0x0, 0x33, 0x0, 0x98, 0xFE, 0xA4, 0xFD, 0x50, 0x8B, 0x7, 0x0, 0x8, 0x0, 0x33, 0x0, 0x0, 0x0, 0x0, 0x0, 0xE, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x9E, 0xFE, 0xA6, 0xFD, 0x28, 0x71, 0x7, 0x0, 0x8, 0x0, 0x34, 0x0, 0x60, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x1C, 0x8, 0x0, 0xC0, 0x0, 0x63, 0x2, 0x0, 0x0, 0x0, 0x0, 0xC4, 0x0, 0x5F, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0xB, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x9B, 0x1, 0x0, 0x0, 0x9B, 0x1, 0x0, 0x0, 0x9B, 0x1, 0x0, 0x0, 0x9B, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x9B, 0x1, 0x0, 0x0, 0x9B, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0x9C, 0x1, 0xCE, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFC, 0xFC, 0xA4, 0xFD, 0x20, 0xA9, 0xE, 0x0, 0x8, 0x0, 0x33, 0x0, 0xFC, 0xFC, 0xA4, 0xFD, 0x20, 0xA9, 0xE, 0x0, 0x8, 0x0, 0x33, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x2, 0xFD, 0xA6, 0xFD, 0xA8, 0x7B, 0xE, 0x0, 0x8, 0x0, 0x34, 0x0, 0xC4, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x20, 0x98, 0x7, 0x0, 0x0, 0x0, 0xC7, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0xB, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xC4, 0x0, 0x62, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0xF4, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x3C, 0xFC, 0xA4, 0xFD, 0x20, 0xBF, 0x13, 0x0, 0x8, 0x0, 0x33, 0x0, 0x3C, 0xFC, 0xA4, 0xFD, 0x20, 0xBF, 0x13, 0x0, 0x8, 0x0, 0x33, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x3E, 0xFC, 0xA6, 0xFD, 0xA8, 0xA6, 0x13, 0x0, 0x8, 0x0, 0x34, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xE0, 0x9C, 0x3, 0x0, 0x20, 0x4, 0x1, 0x0, 0x5D, 0x59, 0xAB, 0x0, 0xC8, 0x8C, 0xFD, 0xF4, 0x3, 0x0, 0x0, 0x0, 0xB8, 0x13, 0xFD, 0xFF, 0xAC, 0x5F, 0x8C, 0xF5, 0x0, 0x20, 0x4E, 0x0, 0xAB, 0xAA, 0xAA, 0xAA, 0x40, 0x69, 0xFD, 0xF4, 0x0, 0x0, 0x0, 0x0, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x38, 0x6B, 0x8B, 0xF5, 0x11, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x9F, 0x9, 0x0, 0x0, 0xB8, 0x2B, 0x6B, 0x15, 0xC0, 0x6A, 0x8C, 0xF5, 0x0, 0x0, 0x0, 0x0, 0xB8, 0x13, 0xFD, 0xFF, 0x2A, 0x5, 0x1, 0x0, 0xC0, 0x13, 0xFD, 0xFF, 0x2C, 0x14, 0xFD, 0xFF, 0x14, 0x14, 0xFD, 0xFF, 0xCC, 0xE8, 0x89, 0xF5, 0xC0, 0x13, 0xFD, 0xFF, 0x64, 0x6A, 0x8C, 0xF5, 0x3, 0x0, 0x0, 0x0, 0xA0, 0x6B, 0x8B, 0xF5, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x8, 0x69, 0x8C, 0xF5, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC0, 0x6A, 0x8C, 0xF5, 0x8, 0x69, 0x8C, 0xF5, 0xFF, 0xFF, 0xFF, 0xFF, 0xA0, 0x9, 0x0, 0x0, 0xF8, 0xB2, 0xFD, 0xF4, 0x50, 0x35, 0x8C, 0xF5, 0xD0, 0x14, 0xC1, 0xF4, 0x1, 0xD0, 0x3B, 0xF5, 0x64, 0x1F, 0xFD, 0xFF, 0xD0, 0xAD, 0x4, 0xF5, 0x2C, 0x30, 0x1, 0x0, 0x0, 0x10, 0x0, 0x0, 0x2C, 0x0, 0x0, 0x0, 0x14, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x4C, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC, 0x30, 0x1, 0x0, 0xD0, 0x14, 0xC1, 0xF4, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x10, 0x1F, 0xFD, 0xFF, 0x3C, 0x23, 0xFD, 0x34, 0x31, 0x32, 0x31, 0x36, 0xA0, 0x6B, 0x8B, 0xF5, 0x60, 0x14, 0xFD, 0xFF, 0x0, 0x30, 0x1, 0x0, 0x14, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x4C, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x10, 0x1F, 0xFD, 0xFF, 0x3C, 0x23, 0xFD, 0xFF, 0xC0, 0xDC, 0x1, 0xF5, 0x4C, 0x0, 0x0, 0x0, 0x54, 0x14, 0xFD, 0xFF, 0x50, 0x1D, 0x1, 0x0, 0x30, 0x14, 0x1, 0x0, 0x98, 0x1D, 0x1, 0x0, 0x0, 0xA1, 0x0, 0x0, 0x0, 0xA1, 0x0, 0x0, 0x98, 0x1D, 0x1, 0x0, 0x6C, 0x1F, 0xFD, 0xFF, 0x64, 0x1F, 0xFD, 0xFF, 0x68, 0x1F, 0xFD, 0xFF, 0x0, 0x0, 0x0, 0x0}, - {0x5, 0x0, 0x6, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x4, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x4, 0x0, 0x0, 0xFF, 0xFF, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x4, 0x0, 0x0, 0xB7, 0x4, 0x0, 0x0, 0xB7, 0x4, 0x0, 0x0, 0x5B, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x4, 0x0, 0x0, 0x5B, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x4, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xB8, 0x4, 0x5C, 0x2, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x5, 0x0, 0x0, 0x0, 0x70, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC0, 0x89, 0x23, 0x0, 0x1, 0x0, 0x0, 0x0, 0xCC, 0x5, 0x87, 0x7, 0x0, 0x0, 0x0, 0x0, 0xD0, 0x5, 0x87, 0x7, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0xB, 0x0, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xB8, 0x1, 0xDC, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x2, 0xA4, 0xFD, 0x50, 0xB1, 0x9, 0x0, 0x8, 0x0, 0x33, 0x0, 0x8, 0x2, 0xA4, 0xFD, 0x50, 0xB1, 0x9, 0x0, 0x8, 0x0, 0x33, 0x0, 0x0, 0x0, 0x0, 0x0, 0x6, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xE, 0x2, 0xA6, 0xFD, 0x68, 0xC0, 0x9, 0x0, 0x8, 0x0, 0x34, 0x0, 0xD0, 0x5, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x1C, 0x8, 0x0, 0x14, 0x4, 0xD3, 0x5, 0x0, 0x0, 0x0, 0x0, 0x18, 0x4, 0xCF, 0x5, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0xB, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xB8, 0x1, 0xDC, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x50, 0x0, 0xA4, 0xFD, 0x10, 0xAA, 0x5, 0x0, 0x8, 0x0, 0x33, 0x0, 0x50, 0x0, 0xA4, 0xFD, 0x10, 0xAA, 0x5, 0x0, 0x8, 0x0, 0x33, 0x0, 0x0, 0x0, 0x0, 0x0, 0xA, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x56, 0x0, 0xA6, 0xFD, 0x88, 0xA4, 0x5, 0x0, 0x8, 0x0, 0x34, 0x0, 0x18, 0x4, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x1C, 0x8, 0x0, 0x5C, 0x2, 0x1B, 0x4, 0x0, 0x0, 0x0, 0x0, 0x60, 0x2, 0x17, 0x4, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0xB, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xB8, 0x1, 0xDC, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x98, 0xFE, 0xA4, 0xFD, 0x50, 0x8B, 0x7, 0x0, 0x8, 0x0, 0x33, 0x0, 0x98, 0xFE, 0xA4, 0xFD, 0x50, 0x8B, 0x7, 0x0, 0x8, 0x0, 0x33, 0x0, 0x0, 0x0, 0x0, 0x0, 0xE, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x9E, 0xFE, 0xA6, 0xFD, 0x28, 0x71, 0x7, 0x0, 0x8, 0x0, 0x34, 0x0, 0x60, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x1C, 0x8, 0x0, 0xC0, 0x0, 0x63, 0x2, 0x0, 0x0, 0x0, 0x0, 0xC4, 0x0, 0x5F, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0xB, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x9B, 0x1, 0x0, 0x0, 0x9B, 0x1, 0x0, 0x0, 0x9B, 0x1, 0x0, 0x0, 0x9B, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x9B, 0x1, 0x0, 0x0, 0x9B, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0x9C, 0x1, 0xCE, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFC, 0xFC, 0xA4, 0xFD, 0x20, 0xA9, 0xE, 0x0, 0x8, 0x0, 0x33, 0x0, 0xFC, 0xFC, 0xA4, 0xFD, 0x20, 0xA9, 0xE, 0x0, 0x8, 0x0, 0x33, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x2, 0xFD, 0xA6, 0xFD, 0xA8, 0x7B, 0xE, 0x0, 0x8, 0x0, 0x34, 0x0, 0xC4, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x20, 0x98, 0x7, 0x0, 0x0, 0x0, 0xC7, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0xB, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xC4, 0x0, 0x62, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0xF4, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x3C, 0xFC, 0xA4, 0xFD, 0x20, 0xBF, 0x13, 0x0, 0x8, 0x0, 0x33, 0x0, 0x3C, 0xFC, 0xA4, 0xFD, 0x20, 0xBF, 0x13, 0x0, 0x8, 0x0, 0x33, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x3E, 0xFC, 0xA6, 0xFD, 0xA8, 0xA6, 0x13, 0x0, 0x8, 0x0, 0x34, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xE0, 0x9C, 0x3, 0x0, 0x20, 0x4, 0x1, 0x0, 0xA0, 0x9, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x4, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x60, 0x5D, 0x1, 0x0, 0x0, 0x0, 0x0, 0x7, 0x0, 0x0, 0x0, 0xFC, 0x57, 0x12, 0xF5, 0x0, 0x0, 0x0, 0x0, 0x0, 0x50, 0x12, 0xF5, 0x0, 0x0, 0x0, 0x0, 0x9F, 0x9, 0x0, 0x0, 0x5E, 0x0, 0x0, 0x0, 0x5F, 0x0, 0x0, 0x0, 0x6E, 0x0, 0x0, 0x0, 0x77, 0x0, 0x0, 0x0, 0x7C, 0x0, 0x0, 0x0, 0x35, 0x1, 0x0, 0x0, 0x26, 0x0, 0x0, 0x0, 0xA4, 0x61, 0x5D, 0x1, 0x58, 0x3, 0x0, 0x0, 0xC0, 0x13, 0xFD, 0xFF, 0x64, 0x6A, 0x8C, 0xF5, 0x3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x50, 0x12, 0xF5, 0x9F, 0x9, 0x0, 0x0, 0xA0, 0x9, 0x0, 0x0, 0xFC, 0x57, 0x12, 0xF5, 0x33, 0x1, 0x0, 0x0, 0xD0, 0x14, 0xC1, 0xF4, 0x1, 0xD0, 0x3B, 0xF5, 0x64, 0x1F, 0xFD, 0xFF, 0xD0, 0xAD, 0x4, 0xF5, 0x2C, 0x30, 0x1, 0x0, 0x0, 0x10, 0x0, 0x0, 0x2C, 0x0, 0x0, 0x0, 0x14, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x4C, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x4C, 0x27, 0x5E, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC0, 0x0, 0x0, 0x0, 0x6, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x34, 0x31, 0x32, 0x31, 0x36, 0x10, 0x20, 0xFD, 0xFF, 0x60, 0x14, 0xFD, 0xFF, 0x0, 0x30, 0x1, 0x0, 0xA0, 0x9, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x4C, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x10, 0x1F, 0xFD, 0xFF, 0x3C, 0x23, 0xFD, 0xFF, 0xC0, 0xDC, 0x1, 0xF5, 0x0, 0x30, 0x1, 0x0, 0x54, 0x14, 0xFD, 0xFF, 0x0, 0x0, 0x0, 0x0, 0x30, 0x14, 0x1, 0x0, 0x98, 0x1D, 0x1, 0x0, 0x0, 0xA1, 0x0, 0x0, 0x0, 0xA1, 0x0, 0x0, 0x98, 0x1D, 0x1, 0x0, 0x6C, 0x1F, 0xFD, 0xFF, 0x64, 0x1F, 0xFD, 0xFF, 0x68, 0x1F, 0xFD, 0xFF, 0x0, 0x0, 0x0, 0x0}, - {0x4, 0x0, 0x4, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0xF7, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xF7, 0x2, 0x0, 0x0, 0xFF, 0xFF, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xF7, 0x2, 0x0, 0x0, 0xF7, 0x2, 0x0, 0x0, 0xF7, 0x2, 0x0, 0x0, 0x7B, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xF7, 0x2, 0x0, 0x0, 0x7B, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xF7, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xF8, 0x2, 0x7C, 0x1, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x4, 0x0, 0x2, 0x0, 0x70, 0x1, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x50, 0x0, 0xA4, 0xFD, 0x10, 0xAA, 0x5, 0x0, 0x8, 0x0, 0x33, 0x0, 0x50, 0x0, 0xA4, 0xFD, 0x10, 0xAA, 0x5, 0x0, 0x8, 0x0, 0x33, 0x0, 0x0, 0x0, 0x0, 0x0, 0xA, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x56, 0x0, 0xA6, 0xFD, 0x88, 0xA4, 0x5, 0x0, 0x8, 0x0, 0x34, 0x0, 0x18, 0x4, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x24, 0x0, 0x0, 0x0, 0x78, 0x14, 0x5E, 0x1, 0xB8, 0x5D, 0x12, 0xF5, 0xDC, 0x3B, 0x12, 0xF5, 0x24, 0x0, 0x0, 0x0, 0xFC, 0xF9, 0x3, 0xF5, 0x0, 0x96, 0xF, 0x0, 0x1, 0x5, 0x0, 0x0, 0x84, 0x3, 0x3F, 0x5, 0x0, 0x0, 0x0, 0x0, 0x88, 0x3, 0x3F, 0x5, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0xB, 0x0, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xB8, 0x1, 0xDC, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xE4, 0x0, 0x84, 0xFE, 0x20, 0xFF, 0x2, 0x0, 0x7, 0x0, 0x38, 0x0, 0xE4, 0x0, 0x84, 0xFE, 0x20, 0xFF, 0x2, 0x0, 0x7, 0x0, 0x38, 0x0, 0x0, 0x0, 0x0, 0x0, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xEA, 0x0, 0x86, 0xFE, 0x8, 0x4, 0x3, 0x0, 0x7, 0x0, 0x38, 0x0, 0x88, 0x3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x1A, 0x5, 0x0, 0xCC, 0x1, 0x8B, 0x3, 0x0, 0x0, 0x0, 0x0, 0xD0, 0x1, 0x87, 0x3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0xB, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xB8, 0x1, 0xDC, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x2C, 0xFF, 0x84, 0xFE, 0xA0, 0xE3, 0x2, 0x0, 0x7, 0x0, 0x38, 0x0, 0x2C, 0xFF, 0x84, 0xFE, 0xA0, 0xE3, 0x2, 0x0, 0x7, 0x0, 0x38, 0x0, 0x0, 0x0, 0x0, 0x0, 0x6, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x32, 0xFF, 0x86, 0xFE, 0xE8, 0xD3, 0x2, 0x0, 0x7, 0x0, 0x38, 0x0, 0xD0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x1A, 0x5, 0x0, 0xC0, 0x0, 0xD3, 0x1, 0x0, 0x0, 0x0, 0x0, 0xC4, 0x0, 0xCF, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0xB, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB, 0x1, 0x0, 0x0, 0xB, 0x1, 0x0, 0x0, 0xB, 0x1, 0x0, 0x0, 0xB, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB, 0x1, 0x0, 0x0, 0xB, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xC, 0x1, 0x86, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0xF4, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x20, 0xFE, 0x84, 0xFE, 0x10, 0xB8, 0x5, 0x0, 0x7, 0x0, 0x38, 0x0, 0x20, 0xFE, 0x84, 0xFE, 0x10, 0xB8, 0x5, 0x0, 0x7, 0x0, 0x38, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x26, 0xFE, 0x86, 0xFE, 0xC8, 0x9B, 0x5, 0x0, 0x7, 0x0, 0x38, 0x0, 0xC4, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xA0, 0x1B, 0x3, 0x0, 0x0, 0x0, 0xC7, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0xB, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xC4, 0x0, 0x62, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0xF5, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x60, 0xFD, 0x84, 0xFE, 0x10, 0x18, 0x9, 0x0, 0x7, 0x0, 0x38, 0x0, 0x60, 0xFD, 0x84, 0xFE, 0x10, 0x18, 0x9, 0x0, 0x7, 0x0, 0x38, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x62, 0xFD, 0x86, 0xFE, 0xA8, 0x7, 0x9, 0x0, 0x7, 0x0, 0x38, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xE0, 0x45, 0x2, 0x0}, +{ /* placeholder */ }, + {0x5, 0x0, 0x6, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x4, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x4, 0x0, 0x0, 0xFF, 0xFF, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x4, 0x0, 0x0, 0xB7, 0x4, 0x0, 0x0, 0xB7, 0x4, 0x0, 0x0, 0x5B, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x4, 0x0, 0x0, 0x5B, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x4, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xB8, 0x4, 0x5C, 0x2, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x5, 0x0, 0x0, 0x0, 0x70, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC0, 0x89, 0x23, 0x0, 0x1, 0x0, 0x0, 0x0, 0xCC, 0x5, 0x87, 0x7, 0x0, 0x0, 0x0, 0x0, 0xD0, 0x5, 0x87, 0x7, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0xB, 0x0, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xB8, 0x1, 0xDC, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x2, 0xA4, 0xFD, 0x50, 0xB1, 0x9, 0x0, 0x8, 0x0, 0x33, 0x0, 0x8, 0x2, 0xA4, 0xFD, 0x50, 0xB1, 0x9, 0x0, 0x8, 0x0, 0x33, 0x0, 0x0, 0x0, 0x0, 0x0, 0x6, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xE, 0x2, 0xA6, 0xFD, 0x68, 0xC0, 0x9, 0x0, 0x8, 0x0, 0x34, 0x0, 0xD0, 0x5, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x1C, 0x8, 0x0, 0x14, 0x4, 0xD3, 0x5, 0x0, 0x0, 0x0, 0x0, 0x18, 0x4, 0xCF, 0x5, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0xB, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xB8, 0x1, 0xDC, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x50, 0x0, 0xA4, 0xFD, 0x10, 0xAA, 0x5, 0x0, 0x8, 0x0, 0x33, 0x0, 0x50, 0x0, 0xA4, 0xFD, 0x10, 0xAA, 0x5, 0x0, 0x8, 0x0, 0x33, 0x0, 0x0, 0x0, 0x0, 0x0, 0xA, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x56, 0x0, 0xA6, 0xFD, 0x88, 0xA4, 0x5, 0x0, 0x8, 0x0, 0x34, 0x0, 0x18, 0x4, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x1C, 0x8, 0x0, 0x5C, 0x2, 0x1B, 0x4, 0x0, 0x0, 0x0, 0x0, 0x60, 0x2, 0x17, 0x4, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0xB, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xB8, 0x1, 0xDC, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x98, 0xFE, 0xA4, 0xFD, 0x50, 0x8B, 0x7, 0x0, 0x8, 0x0, 0x33, 0x0, 0x98, 0xFE, 0xA4, 0xFD, 0x50, 0x8B, 0x7, 0x0, 0x8, 0x0, 0x33, 0x0, 0x0, 0x0, 0x0, 0x0, 0xE, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x9E, 0xFE, 0xA6, 0xFD, 0x28, 0x71, 0x7, 0x0, 0x8, 0x0, 0x34, 0x0, 0x60, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x1C, 0x8, 0x0, 0xC0, 0x0, 0x63, 0x2, 0x0, 0x0, 0x0, 0x0, 0xC4, 0x0, 0x5F, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0xB, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x9B, 0x1, 0x0, 0x0, 0x9B, 0x1, 0x0, 0x0, 0x9B, 0x1, 0x0, 0x0, 0x9B, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x9B, 0x1, 0x0, 0x0, 0x9B, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0x9C, 0x1, 0xCE, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFC, 0xFC, 0xA4, 0xFD, 0x20, 0xA9, 0xE, 0x0, 0x8, 0x0, 0x33, 0x0, 0xFC, 0xFC, 0xA4, 0xFD, 0x20, 0xA9, 0xE, 0x0, 0x8, 0x0, 0x33, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x2, 0xFD, 0xA6, 0xFD, 0xA8, 0x7B, 0xE, 0x0, 0x8, 0x0, 0x34, 0x0, 0xC4, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x20, 0x98, 0x7, 0x0, 0x0, 0x0, 0xC7, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0xB, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xC4, 0x0, 0x62, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x3C, 0xFC, 0xA4, 0xFD, 0x20, 0xBF, 0x13, 0x0, 0x8, 0x0, 0x33, 0x0, 0x3C, 0xFC, 0xA4, 0xFD, 0x20, 0xBF, 0x13, 0x0, 0x8, 0x0, 0x33, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x3E, 0xFC, 0xA6, 0xFD, 0xA8, 0xA6, 0x13, 0x0, 0x8, 0x0, 0x34, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xE0, 0x9C, 0x3, 0x0, 0xEC, 0x3, 0x1, 0x0, 0x5D, 0x59, 0xAB, 0x0, 0xC8, 0xFC, 0xFB, 0x40, 0x3, 0x0, 0x0, 0x0, 0x0, 0xFC, 0x7F, 0x40, 0xAC, 0x1F, 0x84, 0x40, 0x0, 0x20, 0x4E, 0x0, 0xAB, 0xAA, 0xAA, 0xAA, 0x40, 0xD9, 0xFB, 0x40, 0x0, 0x0, 0x0, 0x0, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC8, 0xED, 0x80, 0x40, 0x11, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x9F, 0x9, 0x0, 0x0, 0xB8, 0x2B, 0x6B, 0x15, 0xC0, 0x2A, 0x84, 0x40, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFC, 0x7F, 0x40, 0x0, 0x5, 0x1, 0x0, 0x8, 0xFC, 0x7F, 0x40, 0x74, 0xFC, 0x7F, 0x40, 0x5C, 0xFC, 0x7F, 0x40, 0xCC, 0xA8, 0x81, 0x40, 0x8, 0xFC, 0x7F, 0x40, 0x64, 0x2A, 0x84, 0x40, 0x3, 0x0, 0x0, 0x0, 0x30, 0xEE, 0x80, 0x40, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x8, 0x29, 0x84, 0x40, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC0, 0x2A, 0x84, 0x40, 0x8, 0x29, 0x84, 0x40, 0xFF, 0xFF, 0xFF, 0xFF, 0xA0, 0x9, 0x0, 0x0, 0xF8, 0x22, 0xFC, 0x40, 0xB8, 0x16, 0x80, 0x40, 0xD0, 0x34, 0x84, 0x40, 0x1, 0xB0, 0xAB, 0x40, 0xAC, 0x7, 0x80, 0x40, 0xD0, 0x1D, 0x3, 0x41, 0x30, 0x40, 0x1, 0x0, 0xD0, 0x34, 0x84, 0x40, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x1, 0x0, 0xA4, 0xFC, 0x7F, 0x40, 0x0, 0x0, 0x0, 0x0, 0xC, 0x40, 0x1, 0x0, 0xD0, 0x34, 0x84, 0x40, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x1, 0x0, 0x8C, 0xB, 0x80, 0x34, 0x31, 0x32, 0x31, 0x36, 0x30, 0xEE, 0x80, 0x40, 0xA8, 0xFC, 0x7F, 0x40, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x1, 0x0, 0x58, 0x7, 0x80, 0x40, 0x4C, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x1, 0x0, 0x8C, 0xB, 0x80, 0x40, 0xC0, 0x4C, 0x0, 0x41, 0x4C, 0x0, 0x0, 0x0, 0x9C, 0xFC, 0x7F, 0x40, 0x78, 0x22, 0x1, 0x0, 0xC4, 0x15, 0x1, 0x0, 0xC0, 0x22, 0x1, 0x0, 0x0, 0xA1, 0x0, 0x0, 0x0, 0xA1, 0x0, 0x0, 0xC0, 0x22, 0x1, 0x0, 0xB4, 0x7, 0x80, 0x40, 0xAC, 0x7, 0x80, 0x40, 0xB0, 0x7, 0x80, 0x40, 0x0, 0x0, 0x0, 0x0}, + {0x7, 0x0, 0x8, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0xEF, 0x5, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xEF, 0x5, 0x0, 0x0, 0xFF, 0xFF, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0xF7, 0x2, 0x0, 0x0, 0xEF, 0x5, 0x0, 0x0, 0xEF, 0x5, 0x0, 0x0, 0xEF, 0x5, 0x0, 0x0, 0xF7, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xEF, 0x5, 0x0, 0x0, 0xF7, 0x2, 0x0, 0x0, 0xEF, 0x5, 0x0, 0x0, 0xF7, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xF7, 0x2, 0x0, 0x0, 0x7B, 0x1, 0x0, 0x0, 0xEF, 0x5, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xF0, 0x5, 0xF8, 0x2, 0x0, 0x0, 0x3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xF8, 0x2, 0x7C, 0x1, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xF0, 0x5, 0xF8, 0x2, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x7, 0x0, 0x0, 0x0, 0x70, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x3, 0x0, 0x88, 0x7, 0xB8, 0x4, 0x14, 0x0, 0x88, 0x7, 0xB8, 0x4, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x74, 0x16, 0x80, 0x40, 0x52, 0x5, 0x1, 0x0, 0x1A, 0x3, 0x0, 0x0, 0xC4, 0xED, 0x80, 0x40, 0x98, 0x1, 0x0, 0x0, 0x11, 0x7B, 0x9C, 0x7C, 0x11, 0x7B, 0x9C, 0x7C, 0x14, 0x69, 0x69, 0xD, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xE8, 0x8A, 0xFC, 0x40, 0xB2, 0x4, 0x1, 0x0, 0x11, 0x7B, 0x9C, 0x7C, 0xBC, 0x3, 0x1, 0x0, 0xD8, 0xE3, 0xE4, 0x3, 0xC8, 0xFC, 0xFB, 0x40, 0x3, 0x0, 0x0, 0x0, 0x60, 0xF2, 0x7F, 0x40, 0x0, 0x58, 0x3E, 0x0, 0x1, 0x20, 0x4E, 0x0, 0xC4, 0x8, 0x7F, 0xA, 0x0, 0x0, 0x0, 0x0, 0xC8, 0x8, 0x7F, 0xA, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0xB, 0x64, 0x4, 0x3F, 0x5, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xDB, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xDB, 0x0, 0x0, 0x0, 0x6D, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xB8, 0x1, 0xDC, 0x0, 0x0, 0x0, 0x3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xDC, 0x0, 0x6E, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xB8, 0x1, 0xDC, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x84, 0x3, 0x8, 0xFD, 0x50, 0x2C, 0x15, 0x0, 0x9, 0x0, 0x38, 0x0, 0x84, 0x3, 0x8, 0xFD, 0x50, 0x2C, 0x15, 0x0, 0x9, 0x0, 0x38, 0x0, 0x0, 0x0, 0x0, 0x0, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8A, 0x3, 0xA, 0xFD, 0xC8, 0x4A, 0x15, 0x0, 0x9, 0x0, 0x38, 0x0, 0xC8, 0x8, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x80, 0x34, 0xA, 0x0, 0xC, 0x7, 0xCB, 0x8, 0x0, 0x0, 0x0, 0x0, 0x10, 0x7, 0xC7, 0x8, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0xB, 0x88, 0x3, 0x63, 0x4, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xDB, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xDB, 0x0, 0x0, 0x0, 0x6D, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xB8, 0x1, 0xDC, 0x0, 0x0, 0x0, 0x3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xDC, 0x0, 0x6E, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xB8, 0x1, 0xDC, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xCC, 0x1, 0x8, 0xFD, 0xD0, 0xA, 0xC, 0x0, 0x9, 0x0, 0x38, 0x0, 0xCC, 0x1, 0x8, 0xFD, 0xD0, 0xA, 0xC, 0x0, 0x9, 0x0, 0x38, 0x0, 0x0, 0x0, 0x0, 0x0, 0x6, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xD2, 0x1, 0xA, 0xFD, 0xA8, 0x14, 0xC, 0x0, 0x9, 0x0, 0x38, 0x0, 0x10, 0x7, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x80, 0x34, 0xA, 0x0, 0x54, 0x5, 0x13, 0x7, 0x0, 0x0, 0x0, 0x0, 0x58, 0x5, 0xF, 0x7, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0xB, 0xAC, 0x2, 0x87, 0x3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xDB, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xDB, 0x0, 0x0, 0x0, 0x6D, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xB8, 0x1, 0xDC, 0x0, 0x0, 0x0, 0x3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xDC, 0x0, 0x6E, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xB8, 0x1, 0xDC, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x14, 0x0, 0x8, 0xFD, 0xD0, 0xD1, 0x8, 0x0, 0x9, 0x0, 0x38, 0x0, 0x14, 0x0, 0x8, 0xFD, 0xD0, 0xD1, 0x8, 0x0, 0x9, 0x0, 0x38, 0x0, 0x0, 0x0, 0x0, 0x0, 0xA, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x1A, 0x0, 0xA, 0xFD, 0x8, 0xC7, 0x8, 0x0, 0x9, 0x0, 0x38, 0x0, 0x58, 0x5, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x80, 0x34, 0xA, 0x0, 0x9C, 0x3, 0x5B, 0x5, 0x0, 0x0, 0x0, 0x0, 0xA0, 0x3, 0x57, 0x5, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0xB, 0xD0, 0x1, 0xAB, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xDB, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xDB, 0x0, 0x0, 0x0, 0x6D, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xB8, 0x1, 0xDC, 0x0, 0x0, 0x0, 0x3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xDC, 0x0, 0x6E, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xB8, 0x1, 0xDC, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x1, 0x1, 0x0, 0x40, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x5C, 0xFE, 0x8, 0xFD, 0x50, 0x81, 0xB, 0x0, 0x9, 0x0, 0x38, 0x0, 0x5C, 0xFE, 0x8, 0xFD, 0x50, 0x81, 0xB, 0x0, 0x9, 0x0, 0x38, 0x0, 0x0, 0x0, 0x0, 0x0, 0xE, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x62, 0xFE, 0xA, 0xFD, 0xE8, 0x61, 0xB, 0x0, 0x9, 0x0, 0x38, 0x0, 0xA0, 0x3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x80, 0x34, 0xA, 0x0, 0xE4, 0x1, 0xA3, 0x3, 0x0, 0x0, 0x0, 0x0, 0xE8, 0x1, 0x9F, 0x3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0xB, 0xF4, 0x0, 0xCF, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xDB, 0x0, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0xB7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xDB, 0x0, 0x0, 0x0, 0x6D, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xB8, 0x1, 0xDC, 0x0, 0x0, 0x0, 0x3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xDC, 0x0, 0x6E, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xB8, 0x1, 0xDC, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xA4, 0xFC, 0x8, 0xFD, 0x50, 0x19, 0x14, 0x0, 0x9, 0x0, 0x38, 0x0, 0xA4, 0xFC, 0x8, 0xFD, 0x50, 0x19, 0x14, 0x0, 0x9, 0x0, 0x38, 0x0, 0x0, 0x0, 0x0, 0x0, 0x12, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xAA, 0xFC, 0xA, 0xFD, 0x48, 0xE5, 0x13, 0x0, 0x9, 0x0, 0x38, 0x0, 0xE8, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x80, 0x34, 0xA, 0x0, 0xC0, 0x0, 0xEB, 0x1, 0x0, 0x0, 0x0, 0x0, 0xC4, 0x0, 0xE7, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0xB, 0x62, 0x0, 0xF3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x23, 0x1, 0x0, 0x0, 0x23, 0x1, 0x0, 0x0, 0x23, 0x1, 0x0, 0x0, 0x23, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x23, 0x1, 0x0, 0x0, 0x91, 0x0, 0x0, 0x0, 0x23, 0x1, 0x0, 0x0, 0x23, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x91, 0x0, 0x0, 0x0, 0x48, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0x24, 0x1, 0x92, 0x0, 0x0, 0x0, 0x3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0x92, 0x0, 0x49, 0x0, 0x0, 0x0, 0x3, 0x0, 0x1, 0x0, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0x24, 0x1, 0x92, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x1, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x80, 0xFB, 0x8, 0xFD, 0x40, 0x10, 0x1D, 0x0, 0x9, 0x0, 0x38, 0x0, 0x80, 0xFB, 0x8, 0xFD, 0x40, 0x10, 0x1D, 0x0, 0x9, 0x0, 0x38, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x86, 0xFB, 0xA, 0xFD, 0x88, 0xCE, 0x1C, 0x0, 0x9, 0x0, 0x38, 0x0, 0xC4, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC0, 0xC5, 0x6, 0x0, 0x0, 0x0, 0xC7, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0xB, 0x0, 0x0, 0x61, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0x61, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0xC3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x61, 0x0, 0x0, 0x0, 0x30, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xC4, 0x0, 0x62, 0x0, 0x0, 0x0, 0x3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0x62, 0x0, 0x31, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x0, 0x1, 0x0, 0xC4, 0x0, 0x62, 0x0, 0x0, 0x0, 0x3, 0x0, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x1, 0x1, 0x1, 0x1, 0x0, 0x0, 0x1, 0x1, 0x0, 0x40, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC0, 0xFA, 0x8, 0xFD, 0x40, 0x60, 0x24, 0x0, 0x9, 0x0, 0x38, 0x0, 0xC0, 0xFA, 0x8, 0xFD, 0x40, 0x60, 0x24, 0x0, 0x9, 0x0, 0x38, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC2, 0xFA, 0xA, 0xFD, 0x68, 0x3F, 0x24, 0x0, 0x9, 0x0, 0x38, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC0, 0x8B, 0x4, 0x0, 0xEC, 0x3, 0x1, 0x0, 0x58, 0xC, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x6, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x8, 0x50, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x7, 0x0, 0x0, 0x0, 0xFC, 0xC7, 0x10, 0x41, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC0, 0x10, 0x41, 0x0, 0x0, 0x0, 0x0, 0x57, 0xC, 0x0, 0x0, 0x69, 0x0, 0x0, 0x0, 0x61, 0x0, 0x0, 0x0, 0x6E, 0x0, 0x0, 0x0, 0x77, 0x0, 0x0, 0x0, 0x7C, 0x0, 0x0, 0x0, 0x8C, 0x1, 0x0, 0x0, 0x31, 0x0, 0x0, 0x0, 0xA4, 0x51, 0x1, 0x0, 0x58, 0x3, 0x0, 0x0, 0x8, 0xFC, 0x7F, 0x40, 0x64, 0x2A, 0x84, 0x40, 0x3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC0, 0x10, 0x41, 0x57, 0xC, 0x0, 0x0, 0x58, 0xC, 0x0, 0x0, 0xFC, 0xC7, 0x10, 0x41, 0x8A, 0x1, 0x0, 0x0, 0xD0, 0x34, 0x84, 0x40, 0x1, 0xB0, 0xAB, 0x40, 0xAC, 0x7, 0x80, 0x40, 0xD0, 0x1D, 0x3, 0x41, 0x30, 0x40, 0x1, 0x0, 0xD0, 0x34, 0x84, 0x40, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x1, 0x0, 0xA4, 0xFC, 0x7F, 0x40, 0x0, 0x0, 0x0, 0x0, 0x40, 0x5, 0x0, 0x0, 0x4C, 0x17, 0x2, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xC0, 0x0, 0x0, 0x0, 0x8, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x35, 0x33, 0x32, 0x31, 0x36, 0x68, 0x8, 0x80, 0x40, 0xA8, 0xFC, 0x7F, 0x40, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x1, 0x0, 0x58, 0x7, 0x80, 0x40, 0xA0, 0x9, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x40, 0x1, 0x0, 0x8C, 0xB, 0x80, 0x40, 0xC0, 0x4C, 0x0, 0x41, 0x0, 0x0, 0x0, 0x0, 0x9C, 0xFC, 0x7F, 0x40, 0x58, 0x7, 0x80, 0x40, 0xC4, 0x15, 0x1, 0x0, 0xC0, 0x22, 0x1, 0x0, 0xE0, 0xCF, 0x0, 0x0, 0xE0, 0xCF, 0x0, 0x0, 0xC0, 0x22, 0x1, 0x0, 0xB4, 0x7, 0x80, 0x40, 0xAC, 0x7, 0x80, 0x40, 0xB0, 0x7, 0x80, 0x40, 0x0, 0x0, 0x0, 0x0}, }; unsigned char bps_settings[4][684] = { { /* placeholder */ }, - {0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0x3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0x3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}, - {0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0x3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0x3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}, - {0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0x3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0x3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}, +{ /* placeholder */ }, + {0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0x3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0x3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}, + {0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x1, 0x0, 0x0, 0x0, 0x2, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0x3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0x3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0x3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0xFF, 0x3, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}, }; diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc index 6a7f599ab6..63640920db 100644 --- a/system/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -12,8 +12,6 @@ #include #include -#include "media/cam_sensor_cmn_header.h" - #include "common/params.h" #include "common/swaglog.h" diff --git a/system/camerad/cameras/cdm.cc b/system/camerad/cameras/cdm.cc index d4ef20c48c..8a070fa3aa 100644 --- a/system/camerad/cameras/cdm.cc +++ b/system/camerad/cameras/cdm.cc @@ -1,9 +1,9 @@ #include "cdm.h" #include "stddef.h" -int write_dmi(uint8_t *dst, uint64_t *addr, uint32_t length, uint32_t dmi_addr, uint8_t sel) { +int write_dmi(uint8_t *dst, uint64_t *addr, uint32_t length, uint32_t dmi_addr, uint8_t sel, uint8_t opcode) { struct cdm_dmi_cmd *cmd = (struct cdm_dmi_cmd*)dst; - cmd->cmd = CAM_CDM_CMD_DMI_32; + cmd->cmd = opcode; cmd->length = length - 1; cmd->reserved = 0; cmd->addr = 0; // gets patched in diff --git a/system/camerad/cameras/cdm.h b/system/camerad/cameras/cdm.h index adda600400..d9640cee3e 100644 --- a/system/camerad/cameras/cdm.h +++ b/system/camerad/cameras/cdm.h @@ -6,11 +6,6 @@ #include #include -// our helpers -int write_random(uint8_t *dst, const std::vector &vals); -int write_cont(uint8_t *dst, uint32_t reg, const std::vector &vals); -int write_dmi(uint8_t *dst, uint64_t *addr, uint32_t length, uint32_t dmi_addr, uint8_t sel); - // from drivers/media/platform/msm/camera/cam_cdm/cam_cdm_util.{c,h} enum cam_cdm_command { @@ -32,6 +27,11 @@ enum cam_cdm_command { CAM_CDM_CMD_PRIVATE_BASE_MAX = 0x7F }; +// our helpers +int write_random(uint8_t *dst, const std::vector &vals); +int write_cont(uint8_t *dst, uint32_t reg, const std::vector &vals); +int write_dmi(uint8_t *dst, uint64_t *addr, uint32_t length, uint32_t dmi_addr, uint8_t sel, uint8_t opcode = CAM_CDM_CMD_DMI_32); + /** * struct cdm_regrandom_cmd - Definition for CDM random register command. * @count: Number of register writes diff --git a/system/camerad/cameras/nv12_info.h b/system/camerad/cameras/nv12_info.h index e8eb117406..c0460caee3 100644 --- a/system/camerad/cameras/nv12_info.h +++ b/system/camerad/cameras/nv12_info.h @@ -4,7 +4,115 @@ #include #include -#include "third_party/linux/include/msm_media_info.h" +// NV12 subset copied from media/msm_media_info.h. +#ifndef MSM_MEDIA_ALIGN +#define MSM_MEDIA_ALIGN(__sz, __align) (((__align) & ((__align) - 1)) ? \ + ((((__sz) + (__align) - 1) / (__align)) * (__align)) : \ + (((__sz) + (__align) - 1) & (~((__align) - 1)))) +#endif + +#ifndef MSM_MEDIA_MAX +#define MSM_MEDIA_MAX(__a, __b) ((__a) > (__b) ? (__a) : (__b)) +#endif + +enum color_fmts { + COLOR_FMT_NV12, +}; + +static inline unsigned int VENUS_EXTRADATA_SIZE(int width, int height) { + (void)height; + (void)width; + return 16 * 1024; +} + +static inline unsigned int VENUS_Y_STRIDE(int color_fmt, int width) { + unsigned int stride = 0; + if (!width) goto invalid_input; + + switch (color_fmt) { + case COLOR_FMT_NV12: + stride = MSM_MEDIA_ALIGN(width, 128); + break; + default: + break; + } +invalid_input: + return stride; +} + +static inline unsigned int VENUS_UV_STRIDE(int color_fmt, int width) { + unsigned int stride = 0; + if (!width) goto invalid_input; + + switch (color_fmt) { + case COLOR_FMT_NV12: + stride = MSM_MEDIA_ALIGN(width, 128); + break; + default: + break; + } +invalid_input: + return stride; +} + +static inline unsigned int VENUS_Y_SCANLINES(int color_fmt, int height) { + unsigned int sclines = 0; + if (!height) goto invalid_input; + + switch (color_fmt) { + case COLOR_FMT_NV12: + sclines = MSM_MEDIA_ALIGN(height, 32); + break; + default: + break; + } +invalid_input: + return sclines; +} + +static inline unsigned int VENUS_UV_SCANLINES(int color_fmt, int height) { + unsigned int sclines = 0; + if (!height) goto invalid_input; + + switch (color_fmt) { + case COLOR_FMT_NV12: + sclines = MSM_MEDIA_ALIGN((height + 1) >> 1, 16); + break; + default: + break; + } +invalid_input: + return sclines; +} + +static inline unsigned int VENUS_BUFFER_SIZE(int color_fmt, int width, int height) { + const unsigned int extra_size = VENUS_EXTRADATA_SIZE(width, height); + unsigned int size = 0; + unsigned int y_stride = 0, uv_stride = 0, y_sclines = 0, uv_sclines = 0; + + if (!width || !height) goto invalid_input; + + y_stride = VENUS_Y_STRIDE(color_fmt, width); + uv_stride = VENUS_UV_STRIDE(color_fmt, width); + y_sclines = VENUS_Y_SCANLINES(color_fmt, height); + uv_sclines = VENUS_UV_SCANLINES(color_fmt, height); + + switch (color_fmt) { + case COLOR_FMT_NV12: { + const unsigned int y_plane = y_stride * y_sclines; + const unsigned int uv_plane = uv_stride * uv_sclines + 4096; + size = y_plane + uv_plane + MSM_MEDIA_MAX(extra_size, 8 * y_stride); + size = MSM_MEDIA_ALIGN(size, 4096); + size += MSM_MEDIA_ALIGN(width, 512) * 512; + size = MSM_MEDIA_ALIGN(size, 4096); + break; + } + default: + break; + } +invalid_input: + return size; +} // Returns NV12 aligned (stride, y_height, uv_height, buffer_size) for the given frame dimensions. inline std::tuple get_nv12_info(int width, int height) { diff --git a/system/camerad/cameras/nv12_info.py b/system/camerad/cameras/nv12_info.py index bcb6312d2b..2cadc29364 100644 --- a/system/camerad/cameras/nv12_info.py +++ b/system/camerad/cameras/nv12_info.py @@ -1,5 +1,5 @@ # Python version of system/camerad/cameras/nv12_info.h -# Calculations from third_party/linux/include/msm_media_info.h (VENUS_BUFFER_SIZE) +# Calculations from media/msm_media_info.h (VENUS_BUFFER_SIZE) def align(val: int, alignment: int) -> int: return ((val + alignment - 1) // alignment) * alignment diff --git a/system/camerad/cameras/spectra.cc b/system/camerad/cameras/spectra.cc index ab9d8e069a..0b5f5327f5 100644 --- a/system/camerad/cameras/spectra.cc +++ b/system/camerad/cameras/spectra.cc @@ -10,7 +10,6 @@ #include "media/cam_isp.h" #include "media/cam_icp.h" #include "media/cam_isp_ife.h" -#include "media/cam_sensor_cmn_header.h" #include "media/cam_sync.h" #include "common/util.h" @@ -466,8 +465,11 @@ void SpectraCamera::config_bps(int idx, int request_id) { * BPS = Bayer Processing Segment */ - int size = sizeof(struct cam_packet) + sizeof(struct cam_cmd_buf_desc)*2 + sizeof(struct cam_buf_io_cfg)*2; - size += sizeof(struct cam_patch_desc)*9; + bool needs_downscale = sensor->out_scale > 1; + int num_io_cfgs = needs_downscale ? 3 : 2; + int num_patches = needs_downscale ? 14 : 12; + int size = sizeof(struct cam_packet) + sizeof(struct cam_cmd_buf_desc)*2 + sizeof(struct cam_buf_io_cfg)*num_io_cfgs; + size += sizeof(struct cam_patch_desc)*num_patches; uint32_t cam_packet_handle = 0; auto pkt = m->mem_mgr.alloc(size, &cam_packet_handle); @@ -545,8 +547,15 @@ void SpectraCamera::config_bps(int idx, int request_id) { int cdm_len = 0; if (bps_lin_reg.size() == 0) { + // set first knee pt to do BLC + uint32_t new_knee[8]; + new_knee[0] = sensor->black_level << (14 - sensor->bits_per_pixel); + for (int i = 0; i < 7; i++) { + uint32_t pts = sensor->linearization_pts[i / 2]; + new_knee[i + 1] = (i % 2 == 0) ? (pts >> 16) : (pts & 0xffff); + } for (int i = 0; i < 4; i++) { - bps_lin_reg.push_back(((sensor->linearization_pts[i] & 0xffff) << 0x10) | (sensor->linearization_pts[i] >> 0x10)); + bps_lin_reg.push_back((new_knee[2*i + 1] << 16) | new_knee[2*i]); } } @@ -569,20 +578,24 @@ void SpectraCamera::config_bps(int idx, int request_id) { 0x00000080, 0x00800066, }); - // linearization, EN=0 + // linearization cdm_len += write_cont((unsigned char *)bps_cdm_program_array.ptr + cdm_len, 0x1868, bps_lin_reg); cdm_len += write_cont((unsigned char *)bps_cdm_program_array.ptr + cdm_len, 0x1878, bps_lin_reg); cdm_len += write_cont((unsigned char *)bps_cdm_program_array.ptr + cdm_len, 0x1888, bps_lin_reg); cdm_len += write_cont((unsigned char *)bps_cdm_program_array.ptr + cdm_len, 0x1898, bps_lin_reg); - /* - uint8_t *start = (unsigned char *)bps_cdm_program_array.ptr + cdm_len; uint64_t addr; - cdm_len += write_dmi((unsigned char *)bps_cdm_program_array.ptr + cdm_len, &addr, sensor->linearization_lut.size()*sizeof(uint32_t), 0x1808, 1); - patches.push_back(addr - (uint64_t)start); - */ + cdm_len += write_dmi((unsigned char *)bps_cdm_program_array.ptr + cdm_len, &addr, sensor->linearization_lut.size()*sizeof(uint32_t), 0x1808, 1, CAM_CDM_CMD_DMI); + patches.push_back(addr - (uint64_t)bps_cdm_program_array.ptr); + // color correction cdm_len += write_cont((unsigned char *)bps_cdm_program_array.ptr + cdm_len, 0x2e68, bps_ccm_reg); + // gamma + for (uint8_t ch = 1; ch <= 3; ch++) { + cdm_len += write_dmi((unsigned char *)bps_cdm_program_array.ptr + cdm_len, &addr, sensor->gamma_lut_rgb.size()*sizeof(uint32_t), 0x3208, ch, CAM_CDM_CMD_DMI); + patches.push_back(addr - (uint64_t)bps_cdm_program_array.ptr); + } + cdm_len += build_common_ife_bps((unsigned char *)bps_cdm_program_array.ptr + cdm_len, cc, sensor.get(), patches, false); pa->length = cdm_len - 1; @@ -596,7 +609,7 @@ void SpectraCamera::config_bps(int idx, int request_id) { tmp.header = CAM_ICP_CMD_GENERIC_BLOB_CLK; tmp.header |= (sizeof(cam_icp_clk_bw_request)) << 8; tmp.clk.budget_ns = 0x1fca058; - tmp.clk.frame_cycles = 2329024; // comes from the striping lib + tmp.clk.frame_cycles = sensor->frame_width * sensor->frame_height; // matches striping lib pixelCount tmp.clk.rt_flag = 0x0; tmp.clk.uncompressed_bw = 0x38512180; tmp.clk.compressed_bw = 0x38512180; @@ -611,7 +624,7 @@ void SpectraCamera::config_bps(int idx, int request_id) { } // *** io config *** - pkt->num_io_configs = 2; + pkt->num_io_configs = num_io_cfgs; pkt->io_configs_offset = sizeof(struct cam_cmd_buf_desc)*pkt->num_cmd_buf; struct cam_buf_io_cfg *io_cfg = (struct cam_buf_io_cfg *)((char*)&pkt->payload + pkt->io_configs_offset); { @@ -655,28 +668,69 @@ void SpectraCamera::config_bps(int idx, int request_id) { io_cfg[1].format = CAM_FORMAT_NV12; // TODO: why is this 21 in the dump? should be 12 io_cfg[1].color_space = CAM_COLOR_SPACE_BT601_FULL; - io_cfg[1].resource_type = CAM_ICP_BPS_OUTPUT_IMAGE_FULL; + io_cfg[1].resource_type = needs_downscale ? CAM_ICP_BPS_OUTPUT_IMAGE_REG1 : CAM_ICP_BPS_OUTPUT_IMAGE_FULL; io_cfg[1].fence = sync_objs_bps[idx]; io_cfg[1].direction = CAM_BUF_OUTPUT; io_cfg[1].subsample_pattern = 0x1; io_cfg[1].framedrop_pattern = 0x1; + + if (needs_downscale) { + // downscaling needs a full res placeholder + uint32_t full_stride, full_y_h, full_uv_h, full_yuv_size; + std::tie(full_stride, full_y_h, full_uv_h, full_yuv_size) = get_nv12_info(sensor->frame_width, sensor->frame_height); + io_cfg[2].mem_handle[0] = bps_fullres_dummy.handle; + io_cfg[2].mem_handle[1] = bps_fullres_dummy.handle; + io_cfg[2].planes[0] = (struct cam_plane_cfg){ + .width = sensor->frame_width, + .height = sensor->frame_height, + .plane_stride = full_stride, + .slice_height = full_y_h, + }; + io_cfg[2].planes[1] = (struct cam_plane_cfg){ + .width = sensor->frame_width, + .height = sensor->frame_height / 2, + .plane_stride = full_stride, + .slice_height = full_uv_h, + }; + io_cfg[2].offsets[1] = ALIGNED_SIZE(full_stride * full_y_h, 0x1000); + io_cfg[2].format = CAM_FORMAT_NV12; + io_cfg[2].color_space = CAM_COLOR_SPACE_BT601_FULL; + io_cfg[2].resource_type = CAM_ICP_BPS_OUTPUT_IMAGE_FULL; + io_cfg[2].fence = sync_objs_bps[idx]; + io_cfg[2].direction = CAM_BUF_OUTPUT; + io_cfg[2].subsample_pattern = 0x1; + io_cfg[2].framedrop_pattern = 0x1; + } } // *** patches *** { - assert(patches.size() == 0 | patches.size() == 1); + assert(patches.size() == 0 || patches.size() == 4); pkt->patch_offset = sizeof(struct cam_cmd_buf_desc)*pkt->num_cmd_buf + sizeof(struct cam_buf_io_cfg)*pkt->num_io_configs; if (patches.size() > 0) { - add_patch(pkt.get(), bps_cmd.handle, patches[0], bps_linearization_lut.handle, 0); + // linearization LUT + add_patch(pkt.get(), bps_cdm_program_array.handle, patches[0], bps_linearization_lut.handle, 0); + // gamma LUTs + for (int i = 0; i < 3; i++) { + add_patch(pkt.get(), bps_cdm_program_array.handle, patches[i+1], bps_gamma_lut.handle, 0); + } } // input frame add_patch(pkt.get(), bps_cmd.handle, buf_desc[0].offset + offsetof(bps_tmp, frames[0].ptr[0]), buf_handle_raw[idx], 0); - // output frame - add_patch(pkt.get(), bps_cmd.handle, buf_desc[0].offset + offsetof(bps_tmp, frames[1].ptr[0]), buf_handle_yuv[idx], 0); - add_patch(pkt.get(), bps_cmd.handle, buf_desc[0].offset + offsetof(bps_tmp, frames[1].ptr[1]), buf_handle_yuv[idx], io_cfg[1].offsets[1]); + if (needs_downscale) { + add_patch(pkt.get(), bps_cmd.handle, buf_desc[0].offset + offsetof(bps_tmp, frames[1].ptr[0]), bps_fullres_dummy.handle, 0); + add_patch(pkt.get(), bps_cmd.handle, buf_desc[0].offset + offsetof(bps_tmp, frames[1].ptr[1]), bps_fullres_dummy.handle, io_cfg[2].offsets[1]); + // output frame at REG1 + add_patch(pkt.get(), bps_cmd.handle, buf_desc[0].offset + offsetof(bps_tmp, frames[7].ptr[0]), buf_handle_yuv[idx], 0); + add_patch(pkt.get(), bps_cmd.handle, buf_desc[0].offset + offsetof(bps_tmp, frames[7].ptr[1]), buf_handle_yuv[idx], io_cfg[1].offsets[1]); + } else { + // output frame at FULL + add_patch(pkt.get(), bps_cmd.handle, buf_desc[0].offset + offsetof(bps_tmp, frames[1].ptr[0]), buf_handle_yuv[idx], 0); + add_patch(pkt.get(), bps_cmd.handle, buf_desc[0].offset + offsetof(bps_tmp, frames[1].ptr[1]), buf_handle_yuv[idx], io_cfg[1].offsets[1]); + } // rest of buffers add_patch(pkt.get(), bps_cmd.handle, buf_desc[0].offset + offsetof(bps_tmp, settings_addr), bps_iq.handle, 0); @@ -987,9 +1041,6 @@ 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); }; @@ -1167,13 +1218,39 @@ void SpectraCamera::configICP() { // used internally by the BPS, we just allocate it. // size comes from the BPSStripingLib - bps_cdm_striping_bl.init(m, 0xa100, 0x20, true, m->icp_device_iommu); + bps_cdm_striping_bl.init(m, 0xcfe0, 0x20, true, m->icp_device_iommu); + + if (sensor->out_scale > 1) { + uint32_t full_stride, full_y_h, full_uv_h, full_yuv_size; + std::tie(full_stride, full_y_h, full_uv_h, full_yuv_size) = get_nv12_info(sensor->frame_width, sensor->frame_height); + bps_fullres_dummy.init(m, full_yuv_size, 0x1000, true, m->icp_device_iommu); + } // LUTs - /* + assert(sensor->linearization_lut.size() == 36); bps_linearization_lut.init(m, sensor->linearization_lut.size()*sizeof(uint32_t), 0x20, true, m->icp_device_iommu); - memcpy(bps_linearization_lut.ptr, sensor->linearization_lut.data(), bps_linearization_lut.size); - */ + + // bit shift linearization_lut to bps specs, also compensate for black level here + uint32_t bl = sensor->black_level << (14 - sensor->bits_per_pixel); + uint32_t* bps_lut = (uint32_t*)bps_linearization_lut.ptr; + for (size_t i = 0; i < sensor->linearization_lut.size(); i++) { + size_t seg = i / 4; + size_t ch = i % 4; + if (seg == 0) { + bps_lut[i] = 0; + continue; + } + uint32_t e = sensor->linearization_lut[(seg - 1) * 4 + ch]; + uint32_t base = e & 0x3fff; + uint32_t slope_q11 = (e >> 14) & 0x3fff; + uint32_t slope_q12 = std::min(slope_q11 << 1, 0x3fff); + base = (base > bl) ? (base - bl) : 0; + bps_lut[i] = base | (slope_q12 << 14); + } + + assert(sensor->gamma_lut_rgb.size() == 64); + bps_gamma_lut.init(m, sensor->gamma_lut_rgb.size()*sizeof(uint32_t), 0x20, true, m->icp_device_iommu); + memcpy(bps_gamma_lut.ptr, sensor->gamma_lut_rgb.data(), bps_gamma_lut.size); } void SpectraCamera::configCSIPHY() { diff --git a/system/camerad/cameras/spectra.h b/system/camerad/cameras/spectra.h index 7dd1135254..eb6d95af1c 100644 --- a/system/camerad/cameras/spectra.h +++ b/system/camerad/cameras/spectra.h @@ -30,6 +30,29 @@ const int MIPI_SETTLE_CNT = 33; // Calculated by camera_freqs.py #define OpcodesIFEInitialConfig 0x0 #define OpcodesIFEUpdate 0x1 +// Sensor command values from the SDM845 kernel's private camera header: +// drivers/media/platform/msm/camera/cam_sensor_module/cam_sensor_utils/cam_sensor_cmn_header.h +// These are userspace-visible ioctl payload values, but Qualcomm did not export them through UAPI. +enum { + CAMERA_SENSOR_CMD_TYPE_PROBE = 1, + CAMERA_SENSOR_CMD_TYPE_PWR_UP = 2, + CAMERA_SENSOR_CMD_TYPE_PWR_DOWN = 3, + CAMERA_SENSOR_CMD_TYPE_I2C_INFO = 4, + CAMERA_SENSOR_CMD_TYPE_I2C_RNDM_WR = 5, + CAMERA_SENSOR_CMD_TYPE_WAIT = 9, + + CAMERA_SENSOR_WAIT_OP_SW_UCND = 3, + + CAMERA_SENSOR_I2C_TYPE_BYTE = 1, + CAMERA_SENSOR_I2C_TYPE_WORD = 2, + + I2C_FAST_MODE = 1, + + CAM_SENSOR_PACKET_OPCODE_SENSOR_PROBE = 3, + CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG = 4, + CAM_SENSOR_PACKET_OPCODE_SENSOR_NOP = 127, +}; + std::optional device_acquire(int fd, int32_t session_handle, void *data, uint32_t num_resources=1); int device_config(int fd, int32_t session_handle, int32_t dev_handle, uint64_t packet_handle); int device_control(int fd, int op_code, int session_handle, int dev_handle); @@ -173,6 +196,8 @@ public: SpectraBuf bps_iq; SpectraBuf bps_striping; SpectraBuf bps_linearization_lut; + SpectraBuf bps_gamma_lut; + SpectraBuf bps_fullres_dummy; std::vector bps_lin_reg; std::vector bps_ccm_reg; diff --git a/system/camerad/sensors/os04c10.cc b/system/camerad/sensors/os04c10.cc index 62c26ca809..d14c288b91 100644 --- a/system/camerad/sensors/os04c10.cc +++ b/system/camerad/sensors/os04c10.cc @@ -1,7 +1,7 @@ #include #include "system/camerad/sensors/sensor.h" -#include "third_party/linux/include/msm_camsensor_sdk.h" +#include namespace { @@ -21,27 +21,16 @@ 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; - pixel_size_mm = 0.004; + pixel_size_mm = 0.002; data_word = false; - // hdr_offset = 64 * 2 + 8; // stagger - frame_width = 1344; - frame_height = 760; //760 * 2 + hdr_offset; - frame_stride = (frame_width * 12 / 8); // no alignment + out_scale = 2; + frame_width = 2688; + frame_height = 1520; + frame_stride = frame_width * 12 / 8; extra_height = 0; frame_offset = 0; @@ -65,7 +54,7 @@ OS04C10::OS04C10() { dc_gain_on_grey = 0.9; dc_gain_off_grey = 1.0; exposure_time_min = 2; - exposure_time_max = 1684; + exposure_time_max = 2352; analog_gain_min_idx = 0x0; analog_gain_rec_idx = 0x0; // 1x analog_gain_max_idx = 0x28; diff --git a/system/camerad/sensors/os04c10_registers.h b/system/camerad/sensors/os04c10_registers.h index 28d6b3310c..45512851bc 100644 --- a/system/camerad/sensors/os04c10_registers.h +++ b/system/camerad/sensors/os04c10_registers.h @@ -4,7 +4,7 @@ const struct i2c_random_wr_payload start_reg_array_os04c10[] = {{0x100, 1}}; const struct i2c_random_wr_payload stop_reg_array_os04c10[] = {{0x100, 0}}; const struct i2c_random_wr_payload init_array_os04c10[] = { - // baseed on DP_2688X1520_NEWSTG_MIPI0776Mbps_30FPS_10BIT_FOURLANE + // OS04C10_AA_00_02_17_wAO_2688x1524_MIPI728Mbps_Linear12bit_20FPS_4Lane_MCLK24MHz {0x0103, 0x01}, // software reset // PLL + clocks @@ -93,7 +93,7 @@ const struct i2c_random_wr_payload init_array_os04c10[] = { {0x388b, 0x00}, {0x3c80, 0x10}, {0x3c86, 0x00}, - {0x3c8c, 0x20}, + {0x3c8c, 0x40}, {0x3c9f, 0x01}, {0x3d85, 0x1b}, {0x3d8c, 0x71}, @@ -197,7 +197,7 @@ const struct i2c_random_wr_payload init_array_os04c10[] = { {0x370b, 0x48}, {0x370c, 0x01}, {0x370f, 0x00}, - {0x3714, 0x28}, + {0x3714, 0x24}, {0x3716, 0x04}, {0x3719, 0x11}, {0x371a, 0x1e}, @@ -229,7 +229,7 @@ const struct i2c_random_wr_payload init_array_os04c10[] = { {0x37bd, 0x01}, {0x37bf, 0x26}, {0x37c0, 0x11}, - {0x37c2, 0x14}, + {0x37c2, 0x04}, {0x37cd, 0x19}, {0x37e0, 0x08}, {0x37e6, 0x04}, @@ -239,14 +239,14 @@ const struct i2c_random_wr_payload init_array_os04c10[] = { {0x37d8, 0x02}, {0x37e2, 0x10}, {0x3739, 0x10}, - {0x3662, 0x08}, + {0x3662, 0x10}, {0x37e4, 0x20}, {0x37e3, 0x08}, - {0x37d9, 0x04}, + {0x37d9, 0x08}, {0x4040, 0x00}, - {0x4041, 0x03}, - {0x4008, 0x01}, - {0x4009, 0x06}, + {0x4041, 0x07}, + {0x4008, 0x02}, + {0x4009, 0x0d}, // FSIN - frame sync {0x3002, 0x22}, @@ -267,20 +267,20 @@ const struct i2c_random_wr_payload init_array_os04c10[] = { {0x3802, 0x00}, {0x3803, 0x00}, {0x3804, 0x0a}, {0x3805, 0x8f}, {0x3806, 0x05}, {0x3807, 0xff}, - {0x3808, 0x05}, {0x3809, 0x40}, - {0x380a, 0x02}, {0x380b, 0xf8}, + {0x3808, 0x0a}, {0x3809, 0x80}, + {0x380a, 0x05}, {0x380b, 0xf0}, {0x3811, 0x08}, {0x3813, 0x08}, - {0x3814, 0x03}, + {0x3814, 0x01}, {0x3815, 0x01}, - {0x3816, 0x03}, + {0x3816, 0x01}, {0x3817, 0x01}, - {0x380c, 0x0b}, {0x380d, 0xac}, // HTS (line length) - {0x380e, 0x06}, {0x380f, 0x9c}, // VTS (frame length) + {0x380c, 0x08}, {0x380d, 0x5c}, // HTS (line length) + {0x380e, 0x09}, {0x380f, 0x38}, // VTS (frame length) - {0x3820, 0xb3}, - {0x3821, 0x01}, + {0x3820, 0xb0}, + {0x3821, 0x00}, {0x3880, 0x00}, {0x3882, 0x20}, {0x3c91, 0x0b}, @@ -330,23 +330,3 @@ 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[] = { - // based on 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.cc b/system/camerad/sensors/ox03c10.cc index 05d58f03c6..e0e0dec2ff 100644 --- a/system/camerad/sensors/ox03c10.cc +++ b/system/camerad/sensors/ox03c10.cc @@ -1,7 +1,7 @@ #include #include "system/camerad/sensors/sensor.h" -#include "third_party/linux/include/msm_camsensor_sdk.h" +#include namespace { diff --git a/system/camerad/sensors/sensor.h b/system/camerad/sensors/sensor.h index 96aa8b604f..1a647d1528 100644 --- a/system/camerad/sensors/sensor.h +++ b/system/camerad/sensors/sensor.h @@ -98,7 +98,6 @@ 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.py b/system/camerad/snapshot.py index 035a4acdcf..ec6cbc8ad3 100755 --- a/system/camerad/snapshot.py +++ b/system/camerad/snapshot.py @@ -87,7 +87,7 @@ def snapshot(): return None, None front_camera_allowed = params.get_bool("RecordFront") - params.put_bool("IsTakingSnapshot", True) + params.put_bool("IsTakingSnapshot", True, block=True) set_offroad_alert("Offroad_IsTakingSnapshot", True) time.sleep(2.0) # Give hardwared time to read the param, or if just started give camerad time to start @@ -95,7 +95,7 @@ def snapshot(): try: subprocess.check_call(["pgrep", "camerad"]) print("Camerad already running") - params.put_bool("IsTakingSnapshot", False) + params.put_bool("IsTakingSnapshot", False, block=True) params.remove("Offroad_IsTakingSnapshot") return None, None except subprocess.CalledProcessError: @@ -111,7 +111,7 @@ def snapshot(): rear, front = get_snapshots(frame, front_frame) finally: managed_processes['camerad'].stop() - params.put_bool("IsTakingSnapshot", False) + params.put_bool("IsTakingSnapshot", False, block=True) set_offroad_alert("Offroad_IsTakingSnapshot", False) if not front_camera_allowed: diff --git a/system/camerad/test/debug.sh b/system/camerad/test/debug.sh index a031be6923..eba167ce6a 100755 --- a/system/camerad/test/debug.sh +++ b/system/camerad/test/debug.sh @@ -8,7 +8,7 @@ echo 0xfffdbfff | sudo tee /sys/module/cam_debug_util/parameters/debug_mdl #echo 0 | sudo tee /sys/module/cam_debug_util/parameters/debug_mdl sudo dmesg -C -scons -u -j8 --minimal . +scons -u --minimal . export DEBUG_FRAMES=1 export DISABLE_ROAD=1 DISABLE_WIDE_ROAD=1 #export DISABLE_DRIVER=1 diff --git a/system/hardware/base.py b/system/hardware/base.py index ef2b146043..5bcf886ae8 100644 --- a/system/hardware/base.py +++ b/system/hardware/base.py @@ -20,6 +20,10 @@ class Profile: enabled: bool provider: str + @property + def is_comma(self) -> bool: + return self.provider == 'Webbing' and self.iccid.startswith('8985235') + @dataclass class ThermalZone: # a zone from /sys/class/thermal/thermal_zone* @@ -94,8 +98,9 @@ class LPABase(ABC): def process_notifications(self) -> None: pass - def is_comma_profile(self, iccid: str) -> bool: - return any(iccid.startswith(prefix) for prefix in ('8985235',)) + @abstractmethod + def is_euicc(self) -> bool: + pass class HardwareBase(ABC): @staticmethod @@ -194,12 +199,6 @@ class HardwareBase(ABC): def initialize_hardware(self): pass - def configure_modem(self): - pass - - def reboot_modem(self): - pass - def get_networks(self): return None diff --git a/system/hardware/esim.py b/system/hardware/esim.py index 40600d26b5..18d84de983 100755 --- a/system/hardware/esim.py +++ b/system/hardware/esim.py @@ -2,34 +2,69 @@ import argparse from openpilot.system.hardware import HARDWARE +from openpilot.system.hardware.base import LPABase, Profile + + +def sorted_profiles(lpa: LPABase) -> list[Profile]: + return sorted(lpa.list_profiles(), key=lambda p: p.iccid) + + +def resolve_iccid(lpa: LPABase, ref: str) -> str: + # ref is either a 1-based index into the sorted list, or a literal iccid + if ref.isdigit(): + profiles = sorted_profiles(lpa) + idx = int(ref) - 1 + if not 0 <= idx < len(profiles): + raise SystemExit(f'no profile at index {ref} (have {len(profiles)})') + return profiles[idx].iccid + return ref + + +def print_profiles(lpa: LPABase) -> None: + profiles = sorted_profiles(lpa) + print(f'\n{len(profiles)} profile{"s" if len(profiles) != 1 else ""}:') + for i, p in enumerate(profiles, start=1): + print(f'{i}. {p.iccid} (nickname: {p.nickname or ""}) (provider: {p.provider}) - {"enabled" if p.enabled else "disabled"}') if __name__ == '__main__': parser = argparse.ArgumentParser(prog='esim.py', description='manage eSIM profiles on your comma device', epilog='comma.ai') - parser.add_argument('--switch', metavar='iccid', help='switch to 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') + sub = parser.add_subparsers(dest='cmd') + + sub.add_parser('list', help='list profiles') + + p_switch = sub.add_parser('switch', help='switch to profile') + p_switch.add_argument('profile', help='iccid or 1-based index from `list`') + + p_delete = sub.add_parser('delete', help='delete profile (warning: this cannot be undone)') + p_delete.add_argument('profile', help='iccid or 1-based index from `list`') + + p_download = sub.add_parser('download', help='download a profile using QR code (format: LPA:1$rsp.truphone.com$QRF-SPEEDTEST)') + p_download.add_argument('qr') + p_download.add_argument('name') + + p_nickname = sub.add_parser('nickname', help='update the nickname for a profile') + p_nickname.add_argument('profile', help='iccid or 1-based index from `list`') + p_nickname.add_argument('name') + args = parser.parse_args() lpa = HARDWARE.get_sim_lpa() - if args.switch: - lpa.switch_profile(args.switch) - elif args.delete: - confirm = input('are you sure you want to delete this profile? (y/N) ') + if args.cmd == 'switch': + lpa.switch_profile(resolve_iccid(lpa, args.profile)) + elif args.cmd == 'delete': + iccid = resolve_iccid(lpa, args.profile) + confirm = input(f'are you sure you want to delete profile {iccid}? (y/N) ') if confirm == 'y': - lpa.delete_profile(args.delete) + lpa.delete_profile(iccid) 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]) + elif args.cmd == 'download': + lpa.download_profile(args.qr, args.name) + elif args.cmd == 'nickname': + lpa.nickname_profile(resolve_iccid(lpa, args.profile), args.name) 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"}') + if args.cmd is None: + parser.print_help() + print_profiles(lpa) diff --git a/system/hardware/fan_controller.py b/system/hardware/fan_controller.py index b2140d33d4..eafde599ad 100755 --- a/system/hardware/fan_controller.py +++ b/system/hardware/fan_controller.py @@ -2,6 +2,11 @@ import numpy as np from openpilot.common.pid import PIDController +from openpilot.system.hardware import HARDWARE + +# raise fan setpoint on tici/tizi to reduce noise +# after raising LMH threshold in AGNOS 18.1 to prevent CPU throttling +OFFSET = 0 if HARDWARE.get_device_type() == "mici" else 5 class FanController: @@ -18,6 +23,6 @@ class FanController: self.last_ignition = ignition return int(self.controller.update( - error=(cur_temp - 75), # temperature setpoint in C - feedforward=np.interp(cur_temp, [60.0, 100.0], [0, 100]) + error=(cur_temp - (75 + OFFSET)), # temperature setpoint in C + feedforward=np.interp(cur_temp, [60.0 + OFFSET, 100.0 + OFFSET], [0, 100]) )) diff --git a/system/hardware/hardwared.py b/system/hardware/hardwared.py index d4d28418a3..6c84ccfe8a 100755 --- a/system/hardware/hardwared.py +++ b/system/hardware/hardwared.py @@ -40,15 +40,21 @@ HardwareState = namedtuple("HardwareState", ['network_type', 'network_info', 'ne # List of thermal bands. We will stay within this region as long as we are within the bounds. # When exiting the bounds, we'll jump to the lower or higher band. Bands are ordered in the dict. -THERMAL_BANDS = OrderedDict({ - ThermalStatus.green: ThermalBand(None, 80.0), - ThermalStatus.yellow: ThermalBand(75.0, 96.0), - ThermalStatus.red: ThermalBand(88.0, 107.), - ThermalStatus.danger: ThermalBand(94.0, None), -}) +if HARDWARE.get_device_type() == "mici": + THERMAL_BANDS = OrderedDict({ + ThermalStatus.ok: ThermalBand(None, 100.0), + ThermalStatus.overheated: ThermalBand(92.0, 107.), + ThermalStatus.critical: ThermalBand(98.0, None), + }) +else: + THERMAL_BANDS = OrderedDict({ + ThermalStatus.ok: ThermalBand(None, 96.0), + ThermalStatus.overheated: ThermalBand(88.0, 107.), + ThermalStatus.critical: ThermalBand(94.0, None), + }) # Override to highest thermal band when offroad and above this temp -OFFROAD_DANGER_TEMP = 75 +OFFROAD_DANGER_TEMP = 85 if HARDWARE.get_device_type() == "mici" else 75 prev_offroad_states: dict[str, tuple[bool, str | None]] = {} @@ -101,9 +107,6 @@ def hw_state_thread(end_event, hw_queue): prev_hw_state = None modem_version = None - modem_configured = False - modem_missing_count = 0 - modem_restart_count = 0 while not end_event.is_set(): # these are expensive calls. update every 10s @@ -121,18 +124,6 @@ def hw_state_thread(end_event, hw_queue): if modem_version is not None: cloudlog.event("modem version", version=modem_version) - if AGNOS and modem_restart_count < 3 and HARDWARE.get_modem_version() is None: - # TODO: we may be able to remove this with a MM update - # ModemManager's probing on startup can fail - # rarely, restart the service to probe again. - # Also, AT commands sometimes timeout resulting in ModemManager not - # trying to use this modem anymore. - modem_missing_count += 1 - if (modem_missing_count % 4) == 0: - modem_restart_count += 1 - cloudlog.event("restarting ModemManager") - os.system("sudo systemctl restart --no-block ModemManager") - tx, rx = HARDWARE.get_modem_data_usage() hw_state = HardwareState( @@ -149,11 +140,6 @@ def hw_state_thread(end_event, hw_queue): except queue.Full: pass - if not modem_configured and HARDWARE.get_modem_version() is not None: - cloudlog.warning("configuring modem") - HARDWARE.configure_modem() - modem_configured = True - prev_hw_state = hw_state except Exception: cloudlog.exception("Error getting hardware state") @@ -180,7 +166,7 @@ def hardware_thread(end_event, hw_queue) -> None: started_ts: float | None = None started_seen = False startup_blocked_ts: float | None = None - thermal_status = ThermalStatus.yellow + thermal_status = ThermalStatus.ok last_hw_state = HardwareState( network_type=NetworkType.none, @@ -219,7 +205,7 @@ def hardware_thread(end_event, hw_queue) -> None: # handle requests to cycle system started state if params.get_bool("OnroadCycleRequested"): - params.put_bool("OnroadCycleRequested", False) + params.put_bool("OnroadCycleRequested", False, block=True) offroad_cycle_count = sm.frame onroad_conditions["not_onroad_cycle"] = (sm.frame - offroad_cycle_count) >= ONROAD_CYCLE_TIME * SERVICE_LIST['pandaStates'].frequency @@ -288,7 +274,7 @@ def hardware_thread(end_event, hw_queue) -> None: if is_offroad_for_5_min and offroad_comp_temp > OFFROAD_DANGER_TEMP: # if device is offroad and already hot without the extra onroad load, # we want to cool down first before increasing load - thermal_status = ThermalStatus.danger + thermal_status = ThermalStatus.critical else: current_band = THERMAL_BANDS[thermal_status] band_idx = list(THERMAL_BANDS.keys()).index(thermal_status) @@ -312,7 +298,7 @@ def hardware_thread(end_event, hw_queue) -> None: startup_conditions["not_taking_snapshot"] = not params.get_bool("IsTakingSnapshot") # must be at an engageable thermal band to go onroad - startup_conditions["device_temp_engageable"] = thermal_status < ThermalStatus.red + startup_conditions["device_temp_engageable"] = thermal_status < ThermalStatus.overheated # ensure device is fully booted startup_conditions["device_booted"] = startup_conditions.get("device_booted", False) or HARDWARE.booted() @@ -333,7 +319,7 @@ def hardware_thread(end_event, hw_queue) -> None: set_offroad_alert("Offroad_TiciSupport", is_unsupported_combo, extra_text=build_metadata.channel) # if the temperature enters the danger zone, go offroad to cool down - onroad_conditions["device_temp_good"] = thermal_status < ThermalStatus.danger + onroad_conditions["device_temp_good"] = thermal_status < ThermalStatus.critical extra_text = f"{offroad_comp_temp:.1f}C" show_alert = (not onroad_conditions["device_temp_good"] or not startup_conditions["device_temp_engageable"]) and onroad_conditions["ignition"] set_offroad_alert_if_changed("Offroad_TemperatureTooHigh", show_alert, extra_text=extra_text) @@ -347,13 +333,13 @@ def hardware_thread(end_event, hw_queue) -> None: should_start = should_start and all(startup_conditions.values()) if should_start != should_start_prev or (count == 0): - params.put_bool("IsEngaged", False) + params.put_bool("IsEngaged", False, block=True) engaged_prev = False if sm.updated['selfdriveState']: engaged = sm['selfdriveState'].enabled if engaged != engaged_prev: - params.put_bool("IsEngaged", engaged) + params.put_bool("IsEngaged", engaged, block=True) engaged_prev = engaged try: @@ -392,7 +378,7 @@ def hardware_thread(end_event, hw_queue) -> None: # GitHub runner auto off: 9V is used as the threshold because most desktop runners # will rarely exceed 5V so 9V is set as our buffer between desk use and car use. - params.put_bool_nonblocking("GithubRunnerSufficientVoltage", ((voltage or 0) and voltage > 9000)) + params.put_bool("GithubRunnerSufficientVoltage", ((voltage or 0) and voltage > 9000)) power_monitor.calculate(voltage, onroad_conditions["ignition"]) msg.deviceState.offroadPowerUsageUwh = power_monitor.get_power_used() @@ -408,7 +394,7 @@ def hardware_thread(end_event, hw_queue) -> None: # Check if we need to shut down if power_monitor.should_shutdown(onroad_conditions["ignition"], in_car, off_ts, started_seen): cloudlog.warning(f"shutting device down, offroad since {off_ts}") - params.put_bool("DoShutdown", True) + params.put_bool("DoShutdown", True, block=True) msg.deviceState.started = started_ts is not None and not offroad_mode msg.deviceState.startedMonoTime = int(1e9*(started_ts or 0)) @@ -454,11 +440,11 @@ def hardware_thread(end_event, hw_queue) -> None: # save last one before going onroad if rising_edge_started: try: - params.put("LastOffroadStatusPacket", dat) + params.put("LastOffroadStatusPacket", dat, block=True) except Exception: cloudlog.exception("failed to save offroad status") - params.put_bool_nonblocking("NetworkMetered", msg.deviceState.networkMetered) + params.put_bool("NetworkMetered", msg.deviceState.networkMetered) now_ts = time.monotonic() if off_ts: @@ -468,8 +454,8 @@ def hardware_thread(end_event, hw_queue) -> None: last_uptime_ts = now_ts if (count % int(60. / DT_HW)) == 0: - params.put("UptimeOffroad", uptime_offroad) - params.put("UptimeOnroad", uptime_onroad) + params.put("UptimeOffroad", uptime_offroad, block=True) + params.put("UptimeOnroad", uptime_onroad, block=True) count += 1 should_start_prev = should_start diff --git a/system/hardware/power_monitoring.py b/system/hardware/power_monitoring.py index d0a1e623a7..50a83682cf 100644 --- a/system/hardware/power_monitoring.py +++ b/system/hardware/power_monitoring.py @@ -56,7 +56,7 @@ class PowerMonitoring: self.car_battery_capacity_uWh = max(self.car_battery_capacity_uWh, 0) self.car_battery_capacity_uWh = min(self.car_battery_capacity_uWh, CAR_BATTERY_CAPACITY_uWh) if now - self.last_save_time >= 10: - self.params.put_nonblocking("CarBatteryCapacity", int(self.car_battery_capacity_uWh)) + self.params.put("CarBatteryCapacity", int(self.car_battery_capacity_uWh)) self.last_save_time = now # First measurement, set integration time diff --git a/system/hardware/tests/test_power_monitoring.py b/system/hardware/tests/test_power_monitoring.py index 451efcd735..f0804c2071 100644 --- a/system/hardware/tests/test_power_monitoring.py +++ b/system/hardware/tests/test_power_monitoring.py @@ -139,7 +139,7 @@ class TestPowerMonitoring: def test_disable_power_down(self, mocker): POWER_DRAW = 0 # To stop shutting down for other reasons TEST_TIME = 100 - self.params.put_bool("DisablePowerDown", True) + self.params.put_bool("DisablePowerDown", True, block=True) pm_patch(mocker, "HARDWARE.get_current_power_draw", POWER_DRAW) pm = PowerMonitoring() pm.car_battery_capacity_uWh = CAR_BATTERY_CAPACITY_uWh @@ -223,7 +223,7 @@ class TestPowerMonitoring: def test_max_time_offroad_exceeded(self, max_time_offroad, offroad_time_min, expected_result): # Set the parameter if provided if max_time_offroad is not None: - self.params.put("MaxTimeOffroad", max_time_offroad) + self.params.put("MaxTimeOffroad", max_time_offroad, block=True) # Convert offroad time from minutes to seconds offroad_time_s = offroad_time_min * 60 diff --git a/system/hardware/tici/agnos.json b/system/hardware/tici/agnos.json index 295b0279d9..07e2079ec9 100644 --- a/system/hardware/tici/agnos.json +++ b/system/hardware/tici/agnos.json @@ -1,83 +1,83 @@ [ { "name": "xbl", - "url": "https://commadist.azureedge.net/agnosupdate/xbl-dd45c0febdf0e022dab82ed0219370a86e8e6c0dfabfe29f3dab7eb1174d6bc6.img.xz", - "hash": "dd45c0febdf0e022dab82ed0219370a86e8e6c0dfabfe29f3dab7eb1174d6bc6", - "hash_raw": "dd45c0febdf0e022dab82ed0219370a86e8e6c0dfabfe29f3dab7eb1174d6bc6", + "url": "https://commadist.azureedge.net/agnosupdate/xbl-e8acf2a9cc7f0ce84cb803bfea9477f765c0d7b4daf26048e59651b9e6a7bfbb.img.xz", + "hash": "e8acf2a9cc7f0ce84cb803bfea9477f765c0d7b4daf26048e59651b9e6a7bfbb", + "hash_raw": "e8acf2a9cc7f0ce84cb803bfea9477f765c0d7b4daf26048e59651b9e6a7bfbb", "size": 3282256, "sparse": false, "full_check": true, "has_ab": true, - "ondevice_hash": "d47a08914d2376557b03f1231b7233508222c04b57d781f9daf77c63eab92c2e" + "ondevice_hash": "bea7f1a24428c3ededf672fa4fc78baf180cfbd8aafb77c974655b38517283e3" }, { "name": "xbl_config", - "url": "https://commadist.azureedge.net/agnosupdate/xbl_config-1074ae051df159ba6dba988d8f6ba2cfc304ed1466cce0db531df6f7b1e44aa9.img.xz", - "hash": "1074ae051df159ba6dba988d8f6ba2cfc304ed1466cce0db531df6f7b1e44aa9", - "hash_raw": "1074ae051df159ba6dba988d8f6ba2cfc304ed1466cce0db531df6f7b1e44aa9", + "url": "https://commadist.azureedge.net/agnosupdate/xbl_config-758552ecf92b5569677197783bf0ccb73d7f961685308e45d3276ac9dd974f85.img.xz", + "hash": "758552ecf92b5569677197783bf0ccb73d7f961685308e45d3276ac9dd974f85", + "hash_raw": "758552ecf92b5569677197783bf0ccb73d7f961685308e45d3276ac9dd974f85", "size": 98124, "sparse": false, "full_check": true, "has_ab": true, - "ondevice_hash": "e7d04d9f040c9c040cdf013335d0b6d6e9346311458baeb2461b193e954f5f1c" + "ondevice_hash": "fb18cde08a98a168961ecd357e92474823046752b94e112f59fe51a6acd7197d" }, { "name": "abl", - "url": "https://commadist.azureedge.net/agnosupdate/abl-556bbb4ed1c671402b217bd2f3c07edce4f88b0bbd64e92241b82e396aa9ebee.img.xz", - "hash": "556bbb4ed1c671402b217bd2f3c07edce4f88b0bbd64e92241b82e396aa9ebee", - "hash_raw": "556bbb4ed1c671402b217bd2f3c07edce4f88b0bbd64e92241b82e396aa9ebee", + "url": "https://commadist.azureedge.net/agnosupdate/abl-b6fba807b9bcd66a31f2afb0eba5163ec239693ad32e2e4200f6c356adfe098c.img.xz", + "hash": "b6fba807b9bcd66a31f2afb0eba5163ec239693ad32e2e4200f6c356adfe098c", + "hash_raw": "b6fba807b9bcd66a31f2afb0eba5163ec239693ad32e2e4200f6c356adfe098c", "size": 274432, "sparse": false, "full_check": true, "has_ab": true, - "ondevice_hash": "556bbb4ed1c671402b217bd2f3c07edce4f88b0bbd64e92241b82e396aa9ebee" + "ondevice_hash": "b6fba807b9bcd66a31f2afb0eba5163ec239693ad32e2e4200f6c356adfe098c" }, { "name": "aop", - "url": "https://commadist.azureedge.net/agnosupdate/aop-4d925c9248672e4a69a236991983375008c44997a854ee7846d1b5fd7c787788.img.xz", - "hash": "4d925c9248672e4a69a236991983375008c44997a854ee7846d1b5fd7c787788", - "hash_raw": "4d925c9248672e4a69a236991983375008c44997a854ee7846d1b5fd7c787788", + "url": "https://commadist.azureedge.net/agnosupdate/aop-78b2287ca219a0811b3004c523fa0f4749e4d1fd92be3aba61699305b7943ad1.img.xz", + "hash": "78b2287ca219a0811b3004c523fa0f4749e4d1fd92be3aba61699305b7943ad1", + "hash_raw": "78b2287ca219a0811b3004c523fa0f4749e4d1fd92be3aba61699305b7943ad1", "size": 184364, "sparse": false, "full_check": true, "has_ab": true, - "ondevice_hash": "3aa0a79149ec57f4bc8c38f7bbdf4f6630dd659e49a111ce6258d2d06a07c8e5" + "ondevice_hash": "6c9135446bd3fc075fcee59b887a12e49029ab1f98ed8d6d1e32c73569d47de3" }, { "name": "devcfg", - "url": "https://commadist.azureedge.net/agnosupdate/devcfg-2f374581243910db92f62bb13bd66ec8e3d56d434997ba007ded06d2d6cc8585.img.xz", - "hash": "2f374581243910db92f62bb13bd66ec8e3d56d434997ba007ded06d2d6cc8585", - "hash_raw": "2f374581243910db92f62bb13bd66ec8e3d56d434997ba007ded06d2d6cc8585", + "url": "https://commadist.azureedge.net/agnosupdate/devcfg-f71df3a86958c093ba3969254c4db025187eef9385427f1ade946742939b43cc.img.xz", + "hash": "f71df3a86958c093ba3969254c4db025187eef9385427f1ade946742939b43cc", + "hash_raw": "f71df3a86958c093ba3969254c4db025187eef9385427f1ade946742939b43cc", "size": 40336, "sparse": false, "full_check": true, "has_ab": true, - "ondevice_hash": "3d7bb33588491a2a40091a7e1cf6cb65e6dd503f69b640aba484d723f1ad47e8" + "ondevice_hash": "2a67971602012c1b43544964709da13c322786b456a8e78568b117e8b1540ce3" }, { "name": "boot", - "url": "https://commadist.azureedge.net/agnosupdate/boot-d726315cf98a43e1090e5b49297404cf3d084cfbd42ad8bb7d8afb68136b9f51.img.xz", - "hash": "d726315cf98a43e1090e5b49297404cf3d084cfbd42ad8bb7d8afb68136b9f51", - "hash_raw": "d726315cf98a43e1090e5b49297404cf3d084cfbd42ad8bb7d8afb68136b9f51", - "size": 17500160, + "url": "https://commadist.azureedge.net/agnosupdate/boot-8806802b195a5b1396a3ae8dd92a8b7711dc522f6aceafd820e871bae5c8a6d8.img.xz", + "hash": "8806802b195a5b1396a3ae8dd92a8b7711dc522f6aceafd820e871bae5c8a6d8", + "hash_raw": "8806802b195a5b1396a3ae8dd92a8b7711dc522f6aceafd820e871bae5c8a6d8", + "size": 17487872, "sparse": false, "full_check": true, "has_ab": true, - "ondevice_hash": "2454108de1161289bc4a75449ad6421f1772b13b3e5cba68a84fca7530557699" + "ondevice_hash": "edca8bee1531e66953d107eeceeed2dc7b3ca46417e49d55508f94e58bf95db8" }, { "name": "system", - "url": "https://commadist.azureedge.net/agnosupdate/system-dcdea6bd675d0276a63c25151727829620794baf42ada2e5e19a3f77b3f583a5.img.xz", - "hash": "5f319030ad05942267b77f1a4686c4ca24cc09b2c2a4688e57342ffc9720fd49", - "hash_raw": "dcdea6bd675d0276a63c25151727829620794baf42ada2e5e19a3f77b3f583a5", + "url": "https://commadist.azureedge.net/agnosupdate/system-ef0d879302cb29e72110e9c8d3f947c830fd7d37c8192744fc9dbea1af78501f.img.xz", + "hash": "78acfe16a7b62a3a91fc7a81f40a693e4468cec1c69df7d0b1e550aacc646113", + "hash_raw": "ef0d879302cb29e72110e9c8d3f947c830fd7d37c8192744fc9dbea1af78501f", "size": 4718592000, "sparse": true, "full_check": false, "has_ab": true, - "ondevice_hash": "c12f1b7d790a418aea17424accf4cd59c575e5745cad82bdc9452f384483648c", + "ondevice_hash": "743142c5a898f27b2a1029cca42c8a5d5d1fc0096414422b850fe84c8d0b8342", "alt": { - "hash": "dcdea6bd675d0276a63c25151727829620794baf42ada2e5e19a3f77b3f583a5", - "url": "https://commadist.azureedge.net/agnosupdate/system-dcdea6bd675d0276a63c25151727829620794baf42ada2e5e19a3f77b3f583a5.img", + "hash": "ef0d879302cb29e72110e9c8d3f947c830fd7d37c8192744fc9dbea1af78501f", + "url": "https://commadist.azureedge.net/agnosupdate/system-ef0d879302cb29e72110e9c8d3f947c830fd7d37c8192744fc9dbea1af78501f.img", "size": 4718592000 } } diff --git a/system/hardware/tici/all-partitions.json b/system/hardware/tici/all-partitions.json index 0801907a2d..80a0f7702e 100644 --- a/system/hardware/tici/all-partitions.json +++ b/system/hardware/tici/all-partitions.json @@ -130,47 +130,47 @@ }, { "name": "xbl", - "url": "https://commadist.azureedge.net/agnosupdate/xbl-dd45c0febdf0e022dab82ed0219370a86e8e6c0dfabfe29f3dab7eb1174d6bc6.img.xz", - "hash": "dd45c0febdf0e022dab82ed0219370a86e8e6c0dfabfe29f3dab7eb1174d6bc6", - "hash_raw": "dd45c0febdf0e022dab82ed0219370a86e8e6c0dfabfe29f3dab7eb1174d6bc6", + "url": "https://commadist.azureedge.net/agnosupdate/xbl-e8acf2a9cc7f0ce84cb803bfea9477f765c0d7b4daf26048e59651b9e6a7bfbb.img.xz", + "hash": "e8acf2a9cc7f0ce84cb803bfea9477f765c0d7b4daf26048e59651b9e6a7bfbb", + "hash_raw": "e8acf2a9cc7f0ce84cb803bfea9477f765c0d7b4daf26048e59651b9e6a7bfbb", "size": 3282256, "sparse": false, "full_check": true, "has_ab": true, - "ondevice_hash": "d47a08914d2376557b03f1231b7233508222c04b57d781f9daf77c63eab92c2e" + "ondevice_hash": "bea7f1a24428c3ededf672fa4fc78baf180cfbd8aafb77c974655b38517283e3" }, { "name": "xbl_config", - "url": "https://commadist.azureedge.net/agnosupdate/xbl_config-1074ae051df159ba6dba988d8f6ba2cfc304ed1466cce0db531df6f7b1e44aa9.img.xz", - "hash": "1074ae051df159ba6dba988d8f6ba2cfc304ed1466cce0db531df6f7b1e44aa9", - "hash_raw": "1074ae051df159ba6dba988d8f6ba2cfc304ed1466cce0db531df6f7b1e44aa9", + "url": "https://commadist.azureedge.net/agnosupdate/xbl_config-758552ecf92b5569677197783bf0ccb73d7f961685308e45d3276ac9dd974f85.img.xz", + "hash": "758552ecf92b5569677197783bf0ccb73d7f961685308e45d3276ac9dd974f85", + "hash_raw": "758552ecf92b5569677197783bf0ccb73d7f961685308e45d3276ac9dd974f85", "size": 98124, "sparse": false, "full_check": true, "has_ab": true, - "ondevice_hash": "e7d04d9f040c9c040cdf013335d0b6d6e9346311458baeb2461b193e954f5f1c" + "ondevice_hash": "fb18cde08a98a168961ecd357e92474823046752b94e112f59fe51a6acd7197d" }, { "name": "abl", - "url": "https://commadist.azureedge.net/agnosupdate/abl-556bbb4ed1c671402b217bd2f3c07edce4f88b0bbd64e92241b82e396aa9ebee.img.xz", - "hash": "556bbb4ed1c671402b217bd2f3c07edce4f88b0bbd64e92241b82e396aa9ebee", - "hash_raw": "556bbb4ed1c671402b217bd2f3c07edce4f88b0bbd64e92241b82e396aa9ebee", + "url": "https://commadist.azureedge.net/agnosupdate/abl-b6fba807b9bcd66a31f2afb0eba5163ec239693ad32e2e4200f6c356adfe098c.img.xz", + "hash": "b6fba807b9bcd66a31f2afb0eba5163ec239693ad32e2e4200f6c356adfe098c", + "hash_raw": "b6fba807b9bcd66a31f2afb0eba5163ec239693ad32e2e4200f6c356adfe098c", "size": 274432, "sparse": false, "full_check": true, "has_ab": true, - "ondevice_hash": "556bbb4ed1c671402b217bd2f3c07edce4f88b0bbd64e92241b82e396aa9ebee" + "ondevice_hash": "b6fba807b9bcd66a31f2afb0eba5163ec239693ad32e2e4200f6c356adfe098c" }, { "name": "aop", - "url": "https://commadist.azureedge.net/agnosupdate/aop-4d925c9248672e4a69a236991983375008c44997a854ee7846d1b5fd7c787788.img.xz", - "hash": "4d925c9248672e4a69a236991983375008c44997a854ee7846d1b5fd7c787788", - "hash_raw": "4d925c9248672e4a69a236991983375008c44997a854ee7846d1b5fd7c787788", + "url": "https://commadist.azureedge.net/agnosupdate/aop-78b2287ca219a0811b3004c523fa0f4749e4d1fd92be3aba61699305b7943ad1.img.xz", + "hash": "78b2287ca219a0811b3004c523fa0f4749e4d1fd92be3aba61699305b7943ad1", + "hash_raw": "78b2287ca219a0811b3004c523fa0f4749e4d1fd92be3aba61699305b7943ad1", "size": 184364, "sparse": false, "full_check": true, "has_ab": true, - "ondevice_hash": "3aa0a79149ec57f4bc8c38f7bbdf4f6630dd659e49a111ce6258d2d06a07c8e5" + "ondevice_hash": "6c9135446bd3fc075fcee59b887a12e49029ab1f98ed8d6d1e32c73569d47de3" }, { "name": "bluetooth", @@ -207,14 +207,14 @@ }, { "name": "devcfg", - "url": "https://commadist.azureedge.net/agnosupdate/devcfg-2f374581243910db92f62bb13bd66ec8e3d56d434997ba007ded06d2d6cc8585.img.xz", - "hash": "2f374581243910db92f62bb13bd66ec8e3d56d434997ba007ded06d2d6cc8585", - "hash_raw": "2f374581243910db92f62bb13bd66ec8e3d56d434997ba007ded06d2d6cc8585", + "url": "https://commadist.azureedge.net/agnosupdate/devcfg-f71df3a86958c093ba3969254c4db025187eef9385427f1ade946742939b43cc.img.xz", + "hash": "f71df3a86958c093ba3969254c4db025187eef9385427f1ade946742939b43cc", + "hash_raw": "f71df3a86958c093ba3969254c4db025187eef9385427f1ade946742939b43cc", "size": 40336, "sparse": false, "full_check": true, "has_ab": true, - "ondevice_hash": "3d7bb33588491a2a40091a7e1cf6cb65e6dd503f69b640aba484d723f1ad47e8" + "ondevice_hash": "2a67971602012c1b43544964709da13c322786b456a8e78568b117e8b1540ce3" }, { "name": "devinfo", @@ -339,51 +339,51 @@ }, { "name": "boot", - "url": "https://commadist.azureedge.net/agnosupdate/boot-d726315cf98a43e1090e5b49297404cf3d084cfbd42ad8bb7d8afb68136b9f51.img.xz", - "hash": "d726315cf98a43e1090e5b49297404cf3d084cfbd42ad8bb7d8afb68136b9f51", - "hash_raw": "d726315cf98a43e1090e5b49297404cf3d084cfbd42ad8bb7d8afb68136b9f51", - "size": 17500160, + "url": "https://commadist.azureedge.net/agnosupdate/boot-8806802b195a5b1396a3ae8dd92a8b7711dc522f6aceafd820e871bae5c8a6d8.img.xz", + "hash": "8806802b195a5b1396a3ae8dd92a8b7711dc522f6aceafd820e871bae5c8a6d8", + "hash_raw": "8806802b195a5b1396a3ae8dd92a8b7711dc522f6aceafd820e871bae5c8a6d8", + "size": 17487872, "sparse": false, "full_check": true, "has_ab": true, - "ondevice_hash": "2454108de1161289bc4a75449ad6421f1772b13b3e5cba68a84fca7530557699" + "ondevice_hash": "edca8bee1531e66953d107eeceeed2dc7b3ca46417e49d55508f94e58bf95db8" }, { "name": "system", - "url": "https://commadist.azureedge.net/agnosupdate/system-dcdea6bd675d0276a63c25151727829620794baf42ada2e5e19a3f77b3f583a5.img.xz", - "hash": "5f319030ad05942267b77f1a4686c4ca24cc09b2c2a4688e57342ffc9720fd49", - "hash_raw": "dcdea6bd675d0276a63c25151727829620794baf42ada2e5e19a3f77b3f583a5", + "url": "https://commadist.azureedge.net/agnosupdate/system-ef0d879302cb29e72110e9c8d3f947c830fd7d37c8192744fc9dbea1af78501f.img.xz", + "hash": "78acfe16a7b62a3a91fc7a81f40a693e4468cec1c69df7d0b1e550aacc646113", + "hash_raw": "ef0d879302cb29e72110e9c8d3f947c830fd7d37c8192744fc9dbea1af78501f", "size": 4718592000, "sparse": true, "full_check": false, "has_ab": true, - "ondevice_hash": "c12f1b7d790a418aea17424accf4cd59c575e5745cad82bdc9452f384483648c", + "ondevice_hash": "743142c5a898f27b2a1029cca42c8a5d5d1fc0096414422b850fe84c8d0b8342", "alt": { - "hash": "dcdea6bd675d0276a63c25151727829620794baf42ada2e5e19a3f77b3f583a5", - "url": "https://commadist.azureedge.net/agnosupdate/system-dcdea6bd675d0276a63c25151727829620794baf42ada2e5e19a3f77b3f583a5.img", + "hash": "ef0d879302cb29e72110e9c8d3f947c830fd7d37c8192744fc9dbea1af78501f", + "url": "https://commadist.azureedge.net/agnosupdate/system-ef0d879302cb29e72110e9c8d3f947c830fd7d37c8192744fc9dbea1af78501f.img", "size": 4718592000 } }, { "name": "userdata_90", - "url": "https://commadist.azureedge.net/agnosupdate/userdata_90-a7b25ea29255f4fd3a2da99e037f40b4ca10bd4afd57dd96563353b8dfb0f634.img.xz", - "hash": "7ea9d7d4685ec36bbfdf06afe0b51650d567416c3092fef96bd97158ed322742", - "hash_raw": "a7b25ea29255f4fd3a2da99e037f40b4ca10bd4afd57dd96563353b8dfb0f634", + "url": "https://commadist.azureedge.net/agnosupdate/userdata_90-14a3fc6e9bd148b9deebf6ae9df2f1b3b759e629b337e41b6895864cdd51f630.img.xz", + "hash": "52160dd01b30b3dc572226e8d549a034b03bc328e80f1f4cd6a857b6dd447687", + "hash_raw": "14a3fc6e9bd148b9deebf6ae9df2f1b3b759e629b337e41b6895864cdd51f630", "size": 96636764160, "sparse": true, "full_check": true, "has_ab": false, - "ondevice_hash": "79ed653c1679d84b13ee23083a511b0e668454e4af9b0db99a3279072ed041c1" + "ondevice_hash": "3bbc052c7793087946b0cd668c1778f930084f6b00896aeebd193dfce53fa518" }, { "name": "userdata_89", - "url": "https://commadist.azureedge.net/agnosupdate/userdata_89-8e428632c967aa609cac184bff938a90240e53ffd3b4fca40bc94c33c81202ba.img.xz", - "hash": "7104cdb0384e4ecb1ebfa6136a2330251bc8aa829b9ec48c4b740f656252d382", - "hash_raw": "8e428632c967aa609cac184bff938a90240e53ffd3b4fca40bc94c33c81202ba", + "url": "https://commadist.azureedge.net/agnosupdate/userdata_89-425c69d021f4ee2f767963bf7b991d1a492485fa465c5f5d001e1cf7de3d62a0.img.xz", + "hash": "02a8c5512754d7781d930d242be3fad01fbce652297c69dfe8722dc92b18dc09", + "hash_raw": "425c69d021f4ee2f767963bf7b991d1a492485fa465c5f5d001e1cf7de3d62a0", "size": 95563022336, "sparse": true, "full_check": true, "has_ab": false, - "ondevice_hash": "fbede3b0831dbc4a4edd336e5f547f4978902b9421fb1484e86c416192c59165" + "ondevice_hash": "3667d500f91b08a4671d7c09623eb6ae8fc905d9273893b50689e214005c7fa6" } ] \ No newline at end of file diff --git a/system/hardware/tici/esim.nmconnection b/system/hardware/tici/esim.nmconnection deleted file mode 100644 index 74f6f8e82c..0000000000 --- a/system/hardware/tici/esim.nmconnection +++ /dev/null @@ -1,30 +0,0 @@ -[connection] -id=esim -uuid=fff6553c-3284-4707-a6b1-acc021caaafb -type=gsm -permissions= -autoconnect=true -autoconnect-retries=100 -autoconnect-priority=2 -metered=1 - -[gsm] -apn= -home-only=false -auto-config=true -sim-id= - -[ipv4] -route-metric=1000 -dns-priority=1000 -dns-search= -method=auto - -[ipv6] -ddr-gen-mode=stable-privacy -dns-search= -route-metric=1000 -dns-priority=1000 -method=auto - -[proxy] diff --git a/system/hardware/tici/hardware.h b/system/hardware/tici/hardware.h index d59b45efcb..a06ce43b35 100644 --- a/system/hardware/tici/hardware.h +++ b/system/hardware/tici/hardware.h @@ -13,8 +13,11 @@ class HardwareTici : public HardwareNone { public: static std::string get_name() { - std::string model = util::read_file("/sys/firmware/devicetree/base/model"); - return util::strip(model.substr(std::string("comma ").size())); + static const std::string name = []() { + std::string model = util::read_file("/sys/firmware/devicetree/base/model"); + return util::strip(model.substr(std::string("comma ").size())); + }(); + return name; } static cereal::InitData::DeviceType get_device_type() { @@ -23,7 +26,7 @@ public: {"tizi", cereal::InitData::DeviceType::TIZI}, {"mici", cereal::InitData::DeviceType::MICI} }; - auto it = device_map.find(get_name()); + static const auto it = device_map.find(get_name()); assert(it != device_map.end()); return it->second; } diff --git a/system/hardware/tici/hardware.py b/system/hardware/tici/hardware.py index 15c6e41695..34c426d6e7 100644 --- a/system/hardware/tici/hardware.py +++ b/system/hardware/tici/hardware.py @@ -1,9 +1,9 @@ -import math +import configparser +import json import os +import socket import subprocess import time -import tempfile -from enum import IntEnum from functools import cached_property, lru_cache from pathlib import Path @@ -16,51 +16,11 @@ from openpilot.system.hardware.tici.lpa import TiciLPA from openpilot.system.hardware.tici.pins import GPIO from openpilot.system.hardware.tici.amplifier import Amplifier -NM = 'org.freedesktop.NetworkManager' -NM_CON_ACT = NM + '.Connection.Active' -NM_DEV = NM + '.Device' -NM_DEV_WL = NM + '.Device.Wireless' -NM_DEV_STATS = NM + '.Device.Statistics' -NM_AP = NM + '.AccessPoint' -DBUS_PROPS = 'org.freedesktop.DBus.Properties' - -MM = 'org.freedesktop.ModemManager1' -MM_MODEM = MM + ".Modem" -MM_MODEM_SIMPLE = MM + ".Modem.Simple" -MM_SIM = MM + ".Sim" - -class MM_MODEM_STATE(IntEnum): - FAILED = -1 - UNKNOWN = 0 - INITIALIZING = 1 - LOCKED = 2 - DISABLED = 3 - DISABLING = 4 - ENABLING = 5 - ENABLED = 6 - SEARCHING = 7 - REGISTERED = 8 - DISCONNECTING = 9 - CONNECTING = 10 - CONNECTED = 11 - -class NMMetered(IntEnum): - NM_METERED_UNKNOWN = 0 - NM_METERED_YES = 1 - NM_METERED_NO = 2 - NM_METERED_GUESS_YES = 3 - NM_METERED_GUESS_NO = 4 - -TIMEOUT = 0.1 -REFRESH_RATE_MS = 1000 +MODEM_STATE_PATH = "/dev/shm/modem" NetworkType = log.DeviceState.NetworkType NetworkStrength = log.DeviceState.NetworkStrength -# https://developer.gnome.org/ModemManager/unstable/ModemManager-Flags-and-Enumerations.html#MMModemAccessTechnology -MM_MODEM_ACCESS_TECHNOLOGY_UMTS = 1 << 5 -MM_MODEM_ACCESS_TECHNOLOGY_LTE = 1 << 14 - def affine_irq(val, action): irqs = get_irqs_for_action(action) @@ -78,26 +38,40 @@ def get_device_type(): model = f.read().strip('\x00') return model.split('comma ')[-1] +def wpa_supplicant_cmd(cmd: str, timeout: float = 0.2) -> dict[str, str]: + with socket.socket(socket.AF_UNIX, socket.SOCK_DGRAM) as sock: + sock.settimeout(timeout) + sock.bind(f"\0openpilot-wpa-{os.getpid()}-{time.monotonic_ns()}") + sock.connect("/run/wpa_supplicant/wlan0") + sock.send(cmd.encode()) + + while True: + out = sock.recv(8192).decode("utf-8", "replace") + if out.startswith("<"): + continue + if out.startswith("FAIL"): + return {} + return dict(l.split("=", 1) for l in out.splitlines() if "=" in l) + +def get_default_route_iface(): + with open("/proc/net/route") as f: + routes = [(int(route[6]), route[0]) for line in f.readlines()[1:] if (route := line.split())[1] == "00000000" and int(route[3], 16) & 0x1] + return min(routes)[1] if routes else None + class Tici(HardwareBase): - @cached_property - def bus(self): - import dbus - return dbus.SystemBus() - - @cached_property - def nm(self): - return self.bus.get_object(NM, '/org/freedesktop/NetworkManager') - - @property # this should not be cached, in case the modemmanager restarts - def mm(self): - return self.bus.get_object(MM, '/org/freedesktop/ModemManager1') - @cached_property def amplifier(self): if self.get_device_type() == "mici": return None return Amplifier() + def get_modem_state(self) -> dict: + try: + with open(MODEM_STATE_PATH) as f: + return json.load(f) + except (FileNotFoundError, json.JSONDecodeError): + return {} + def get_os_version(self): with open("/VERSION") as f: return f.read().strip() @@ -138,67 +112,37 @@ class Tici(HardwareBase): def get_network_type(self): try: - primary_connection = self.nm.Get(NM, 'PrimaryConnection', dbus_interface=DBUS_PROPS, timeout=TIMEOUT) - primary_connection = self.bus.get_object(NM, primary_connection) - primary_type = primary_connection.Get(NM_CON_ACT, 'Type', dbus_interface=DBUS_PROPS, timeout=TIMEOUT) - - if primary_type == '802-3-ethernet': - return NetworkType.ethernet - elif primary_type == '802-11-wireless': - return NetworkType.wifi - else: - active_connections = self.nm.Get(NM, 'ActiveConnections', dbus_interface=DBUS_PROPS, timeout=TIMEOUT) - for conn in active_connections: - c = self.bus.get_object(NM, conn) - tp = c.Get(NM_CON_ACT, 'Type', dbus_interface=DBUS_PROPS, timeout=TIMEOUT) - if tp == 'gsm': - modem = self.get_modem() - access_t = modem.Get(MM_MODEM, 'AccessTechnologies', dbus_interface=DBUS_PROPS, timeout=TIMEOUT) - if access_t >= MM_MODEM_ACCESS_TECHNOLOGY_LTE: - return NetworkType.cell4G - elif access_t >= MM_MODEM_ACCESS_TECHNOLOGY_UMTS: - return NetworkType.cell3G - else: - return NetworkType.cell2G + if (iface := get_default_route_iface()): + if iface.startswith('wlan'): + return NetworkType.wifi + if iface.startswith('eth'): + return NetworkType.ethernet except Exception: pass + ms = self.get_modem_state() + if ms.get('connected'): + nt = ms.get('network_type', '') + if nt == 'nr': + return NetworkType.cell5G + elif nt == 'lte': + return NetworkType.cell4G + elif nt in ('utran', 'umts'): + return NetworkType.cell3G + elif nt == 'gsm': + return NetworkType.cell2G return NetworkType.none - def get_modem(self): - objects = self.mm.GetManagedObjects(dbus_interface="org.freedesktop.DBus.ObjectManager", timeout=TIMEOUT) - modem_path = list(objects.keys())[0] - return self.bus.get_object(MM, modem_path) - - def get_wlan(self): - wlan_path = self.nm.GetDeviceByIpIface('wlan0', dbus_interface=NM, timeout=TIMEOUT) - return self.bus.get_object(NM, wlan_path) - - def get_wwan(self): - wwan_path = self.nm.GetDeviceByIpIface('wwan0', dbus_interface=NM, timeout=TIMEOUT) - return self.bus.get_object(NM, wwan_path) - def get_sim_info(self): - modem = self.get_modem() - sim_path = modem.Get(MM_MODEM, 'Sim', dbus_interface=DBUS_PROPS, timeout=TIMEOUT) - - if sim_path == "/": - return { - 'sim_id': '', - 'mcc_mnc': None, - 'network_type': ["Unknown"], - 'sim_state': ["ABSENT"], - 'data_connected': False - } - else: - sim = self.bus.get_object(MM, sim_path) - return { - 'sim_id': str(sim.Get(MM_SIM, 'SimIdentifier', dbus_interface=DBUS_PROPS, timeout=TIMEOUT)), - 'mcc_mnc': str(sim.Get(MM_SIM, 'OperatorIdentifier', dbus_interface=DBUS_PROPS, timeout=TIMEOUT)), - 'network_type': ["Unknown"], - 'sim_state': ["READY"], - 'data_connected': modem.Get(MM_MODEM, 'State', dbus_interface=DBUS_PROPS, timeout=TIMEOUT) == MM_MODEM_STATE.CONNECTED, - } + ms = self.get_modem_state() + sim_id = ms.get('iccid', '') + return { + 'sim_id': sim_id, + 'mcc_mnc': ms.get('mcc_mnc') or None, + 'network_type': ["Unknown"], + 'sim_state': ["ABSENT"] if not sim_id else ["READY"], + 'data_connected': ms.get('connected', False), + } def get_sim_lpa(self) -> LPABase: return TiciLPA() @@ -206,40 +150,21 @@ class Tici(HardwareBase): def get_imei(self, slot): if slot != 0: return "" - - return str(self.get_modem().Get(MM_MODEM, 'EquipmentIdentifier', dbus_interface=DBUS_PROPS, timeout=TIMEOUT)) + return self.get_modem_state().get('imei', '') def get_network_info(self): if self.get_device_type() == "mici": return None - try: - modem = self.get_modem() - info = modem.Command("AT+QNWINFO", math.ceil(TIMEOUT), dbus_interface=MM_MODEM, timeout=TIMEOUT) - extra = modem.Command('AT+QENG="servingcell"', math.ceil(TIMEOUT), dbus_interface=MM_MODEM, timeout=TIMEOUT) - state = modem.Get(MM_MODEM, 'State', dbus_interface=DBUS_PROPS, timeout=TIMEOUT) - except Exception: - return None - if info and info.startswith('+QNWINFO: '): - info = info.replace('+QNWINFO: ', '').replace('"', '').split(',') - extra = "" if extra is None else extra.replace('+QENG: "servingcell",', '').replace('"', '') - state = "" if state is None else MM_MODEM_STATE(state).name - - if len(info) != 4: - return None - - technology, operator, band, channel = info - - return({ - 'technology': technology, - 'operator': operator, - 'band': band, - 'channel': int(channel), - 'extra': extra, - 'state': state, - }) - else: - return None + ms = self.get_modem_state() + return { + 'technology': ms.get('network_type', '').upper() if ms.get('network_type') else '', + 'operator': ms.get('operator', ''), + 'band': ms.get('band', ''), + 'channel': ms.get('channel', 0), + 'extra': ms.get('extra', ''), + 'state': ms.get('state', 'UNKNOWN'), + } def parse_strength(self, percentage): if percentage < 25: @@ -257,59 +182,62 @@ class Tici(HardwareBase): try: if network_type == NetworkType.none: pass + elif network_type == NetworkType.ethernet: + network_strength = NetworkStrength.great elif network_type == NetworkType.wifi: - wlan = self.get_wlan() - active_ap_path = wlan.Get(NM_DEV_WL, 'ActiveAccessPoint', dbus_interface=DBUS_PROPS, timeout=TIMEOUT) - if active_ap_path != "/": - active_ap = self.bus.get_object(NM, active_ap_path) - strength = int(active_ap.Get(NM_AP, 'Strength', dbus_interface=DBUS_PROPS, timeout=TIMEOUT)) - network_strength = self.parse_strength(strength) + rssi = wpa_supplicant_cmd("SIGNAL_POLL").get("RSSI") + if rssi is not None: + dbm = int(rssi) + if -100 < dbm <= 0: + network_strength = self.parse_strength(120 + max(-100, min(-20, dbm))) else: # Cellular - modem = self.get_modem() - strength = int(modem.Get(MM_MODEM, 'SignalQuality', dbus_interface=DBUS_PROPS, timeout=TIMEOUT)[0]) - network_strength = self.parse_strength(strength) + network_strength = self.parse_strength(self.get_modem_state().get('signal_quality', 0)) except Exception: pass return network_strength def get_network_metered(self, network_type) -> bool: + if network_type in (NetworkType.cell2G, NetworkType.cell3G, NetworkType.cell4G, NetworkType.cell5G): + from openpilot.common.params import Params + return Params().get_bool("GsmMetered") try: - primary_connection = self.nm.Get(NM, 'PrimaryConnection', dbus_interface=DBUS_PROPS, timeout=TIMEOUT) - primary_connection = self.bus.get_object(NM, primary_connection) - primary_devices = primary_connection.Get(NM_CON_ACT, 'Devices', dbus_interface=DBUS_PROPS, timeout=TIMEOUT) + if network_type == NetworkType.wifi: + ssid = wpa_supplicant_cmd("STATUS").get("ssid", "") + if ssid: + # wpa_supplicant escapes non-printable bytes as \xNN; NM keyfile stores ASCII SSIDs as a literal and others as a byte;byte; list + ssid_bytes = ssid.encode().decode('unicode_escape').encode('latin-1') + ssid_keyfile_list = ';'.join(str(b) for b in ssid_bytes) + ';' - for dev in primary_devices: - dev_obj = self.bus.get_object(NM, str(dev)) - metered_prop = dev_obj.Get(NM_DEV, 'Metered', dbus_interface=DBUS_PROPS, timeout=TIMEOUT) - - if network_type == NetworkType.wifi: - if metered_prop in [NMMetered.NM_METERED_YES, NMMetered.NM_METERED_GUESS_YES]: - return True - elif network_type in [NetworkType.cell2G, NetworkType.cell3G, NetworkType.cell4G, NetworkType.cell5G]: - if metered_prop == NMMetered.NM_METERED_NO: - return False + nm_dirs = ("/run/NetworkManager/system-connections", "/data/etc/NetworkManager/system-connections") + for fpath in (p for d in nm_dirs for p in Path(d).glob("*.nmconnection")): + raw = sudo_read(str(fpath)) + if not raw: + continue + cp = configparser.ConfigParser(interpolation=None) + try: + cp.read_string(raw) + keyfile_ssid = cp.get("wifi", "ssid", fallback="") + if keyfile_ssid != ssid and keyfile_ssid != ssid_keyfile_list: + continue + metered = cp.getint("connection", "metered", fallback=0) + except (configparser.Error, ValueError): + continue + if metered == 1: # NM_METERED_YES + return True + if metered == 2: # NM_METERED_NO + return False + break except Exception: pass return super().get_network_metered(network_type) def get_modem_version(self): - try: - modem = self.get_modem() - return modem.Get(MM_MODEM, 'Revision', dbus_interface=DBUS_PROPS, timeout=TIMEOUT) - except Exception: - return None + return self.get_modem_state().get('modem_version') or None def get_modem_temperatures(self): - 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(filter(lambda t: t != 255, map(int, temps.split(' ')[1].split(',')))) - except Exception: - return [] - + return self.get_modem_state().get('temperatures', []) def get_current_power_draw(self): return (self.read_param_file("/sys/class/hwmon/hwmon1/power1_input", int) / 1e6) @@ -455,68 +383,6 @@ class Tici(HardwareBase): except subprocess.CalledProcessException as e: print(str(e)) - def configure_modem(self): - sim_id = self.get_sim_info().get('sim_id', '') - - cmds = [] - modem = self.get_modem() - - # Quectel EG25 - if self.get_device_type() in ("tizi", ): - # clear out old blue prime initial APN - os.system('mmcli -m any --3gpp-set-initial-eps-bearer-settings="apn="') - - cmds += [ - # SIM hot swap - 'AT+QSIMDET=1,0', - 'AT+QSIMSTAT=1', - - # configure modem as data-centric - 'AT+QNVW=5280,0,"0102000000000000"', - 'AT+QNVFW="/nv/item_files/ims/IMS_enable",00', - 'AT+QNVFW="/nv/item_files/modem/mmode/ue_usage_setting",01', - ] - - # Quectel EG916 - else: - # this modem gets upset with too many AT commands - if sim_id is None or len(sim_id) == 0: - cmds += [ - # SIM sleep disable - 'AT$QCSIMSLEEP=0', - 'AT$QCSIMCFG=SimPowerSave,0', - - # ethernet config - 'AT$QCPCFG=usbNet,1', - ] - - for cmd in cmds: - try: - modem.Command(cmd, math.ceil(TIMEOUT), dbus_interface=MM_MODEM, timeout=TIMEOUT) - except Exception: - pass - - # eSIM prime - dest = "/etc/NetworkManager/system-connections/esim.nmconnection" - if self.get_sim_lpa().is_comma_profile(sim_id) and not os.path.exists(dest): - with open(Path(__file__).parent/'esim.nmconnection') as f, tempfile.NamedTemporaryFile(mode='w') as tf: - dat = f.read() - dat = dat.replace("sim-id=", f"sim-id={sim_id}") - tf.write(dat) - tf.flush() - - # needs to be root - os.system(f"sudo cp {tf.name} {dest}") - os.system(f"sudo nmcli con load {dest}") - - def reboot_modem(self): - modem = self.get_modem() - for state in (0, 1): - try: - modem.Command(f'AT+CFUN={state}', math.ceil(TIMEOUT), dbus_interface=MM_MODEM, timeout=TIMEOUT) - except Exception: - pass - def get_networks(self): r = {} @@ -545,20 +411,8 @@ class Tici(HardwareBase): return r def get_modem_data_usage(self): - try: - wwan = self.get_wwan() - - # Ensure refresh rate is set so values don't go stale - refresh_rate = wwan.Get(NM_DEV_STATS, 'RefreshRateMs', dbus_interface=DBUS_PROPS, timeout=TIMEOUT) - if refresh_rate != REFRESH_RATE_MS: - u = type(refresh_rate) - wwan.Set(NM_DEV_STATS, 'RefreshRateMs', u(REFRESH_RATE_MS), dbus_interface=DBUS_PROPS, timeout=TIMEOUT) - - tx = wwan.Get(NM_DEV_STATS, 'TxBytes', dbus_interface=DBUS_PROPS, timeout=TIMEOUT) - rx = wwan.Get(NM_DEV_STATS, 'RxBytes', dbus_interface=DBUS_PROPS, timeout=TIMEOUT) - return int(tx), int(rx) - except Exception: - return -1, -1 + ms = self.get_modem_state() + return ms.get('tx_bytes', -1), ms.get('rx_bytes', -1) def has_internal_panda(self): return True @@ -569,7 +423,7 @@ class Tici(HardwareBase): gpio_set(GPIO.STM_RST_N, 1) gpio_set(GPIO.STM_BOOT0, 0) - time.sleep(1) + time.sleep(0.01) gpio_set(GPIO.STM_RST_N, 0) def recover_internal_panda(self): @@ -578,9 +432,9 @@ class Tici(HardwareBase): gpio_set(GPIO.STM_RST_N, 1) gpio_set(GPIO.STM_BOOT0, 1) - time.sleep(0.5) + time.sleep(0.01) gpio_set(GPIO.STM_RST_N, 0) - time.sleep(0.5) + time.sleep(0.01) gpio_set(GPIO.STM_BOOT0, 0) def booted(self): @@ -592,7 +446,6 @@ class Tici(HardwareBase): if __name__ == "__main__": t = Tici() - t.configure_modem() t.initialize_hardware() t.set_power_save(False) print(t.get_sim_info()) diff --git a/system/hardware/tici/lpa.py b/system/hardware/tici/lpa.py index e46ac005b8..618d11e5d1 100644 --- a/system/hardware/tici/lpa.py +++ b/system/hardware/tici/lpa.py @@ -4,7 +4,6 @@ import atexit import base64 import fcntl import hashlib -import math import os import requests import serial @@ -20,7 +19,7 @@ from typing import Any from pathlib import Path from openpilot.common.time_helpers import system_time_valid -from openpilot.system.hardware.base import LPABase, LPAError, Profile +from openpilot.system.hardware.base import LPABase, LPAError, LPAProfileNotFoundError, Profile GSMA_CI_BUNDLE = str(Path(__file__).parent / "gsma_ci_bundle.pem") @@ -29,15 +28,13 @@ DEFAULT_BAUD = 9600 DEFAULT_TIMEOUT = 5.0 # https://euicc-manual.osmocom.org/docs/lpa/applet-id/ ISDR_AID = "A0000005591010FFFFFFFF8900000100" -MM = "org.freedesktop.ModemManager1" -MM_MODEM = MM + ".Modem" ES10X_MSS = 120 HTTP_TIMEOUT = 30 OPEN_ISDR_RETRIES = 10 OPEN_ISDR_RETRY_DELAY_S = 0.25 OPEN_ISDR_RESET_ATTEMPT = 5 SEND_APDU_RETRIES = 3 -LOCK_FILE = '/dev/shm/modem_lpa.lock' +LOCK_FILE = '/dev/shm/modem.lock' DEBUG = os.environ.get("DEBUG") == "1" @@ -97,7 +94,7 @@ BPP_ERROR_MESSAGES = { 12: "Profile installation failed. The QR code may have already been used.", } -# SGP.22 §5.2.6 — SM-DP+ reason/subject codes mapped to user-friendly messages +# SGP.22 §5.2.6 SM-DP+ reason/subject codes mapped to user-friendly messages ES9P_ERROR_MESSAGES: dict[tuple[str, str], str] = { ('3.8', '8.2.6'): "This eSIM profile is already installed on another device. Please use a new QR code.", ('3.8', '8.2.1'): "This eSIM profile has expired. Please request a new QR code.", @@ -137,7 +134,6 @@ class AtClient: self._baud = baud self._timeout = timeout self._serial: serial.Serial | None = None - self._use_dbus = not os.path.exists(device) def send_raw(self, data: bytes) -> None: self._ensure_serial() @@ -191,30 +187,7 @@ class AtClient: if self._serial is None: self._serial = serial.Serial(self._device, baudrate=self._baud, timeout=self._timeout) - def _get_modem(self): - import dbus - bus = dbus.SystemBus() - mm = bus.get_object(MM, '/org/freedesktop/ModemManager1') - objects = mm.GetManagedObjects(dbus_interface="org.freedesktop.DBus.ObjectManager", timeout=self._timeout) - modem_path = list(objects.keys())[0] - return bus.get_object(MM, modem_path) - - def _dbus_query(self, cmd: str) -> list[str]: - if DEBUG: - print(f"DBUS >> {cmd}", file=sys.stderr) - try: - result = str(self._get_modem().Command(cmd, math.ceil(self._timeout), dbus_interface=MM_MODEM, timeout=self._timeout)) - except Exception as e: - raise RuntimeError(f"AT command failed: {e}") from e - lines = [line.strip() for line in result.splitlines() if line.strip()] - if DEBUG: - for line in lines: - print(f"DBUS << {line}", file=sys.stderr) - return lines - def query(self, cmd: str) -> list[str]: - if self._use_dbus: - return self._dbus_query(cmd) self._ensure_serial() try: self._send(cmd) @@ -232,7 +205,7 @@ class AtClient: pass self.channel = None # drain any unsolicited responses before opening - if self._serial and not self._use_dbus: + if self._serial: try: self._serial.reset_input_buffer() except (OSError, serial.SerialException, termios.error): @@ -604,8 +577,9 @@ def load_bpp(client: AtClient, b64_bpp: str) -> dict: result = None for chunk in _split_bpp(bpp): response = es10x_command(client, chunk) - if response: - result = _parse_install_result(response) or result + if response and (parsed := _parse_install_result(response)): + result = parsed + break if result is None: raise RuntimeError("Profile installation failed: no result from eUICC") @@ -716,22 +690,29 @@ class TiciLPA(LPABase): atexit.register(self._client.close) @contextmanager - def _acquire_channel(self): + def _acquire_lock(self): fd = os.open(LOCK_FILE, os.O_CREAT | os.O_RDWR) try: fcntl.flock(fd, fcntl.LOCK_EX) - self._client.open_isdr() yield finally: - if self._client.channel: - try: - self._client.query(f"AT+CCHC={self._client.channel}") - except (RuntimeError, TimeoutError): - pass - self._client.channel = None fcntl.flock(fd, fcntl.LOCK_UN) os.close(fd) + @contextmanager + def _acquire_channel(self): + with self._acquire_lock(): + try: + self._client.open_isdr() + yield + finally: + if self._client.channel: + try: + self._client.query(f"AT+CCHC={self._client.channel}") + except (RuntimeError, TimeoutError): + pass + self._client.channel = None + def list_profiles(self) -> list[Profile]: with self._acquire_channel(): return [ @@ -754,7 +735,10 @@ class TiciLPA(LPABase): process_notifications(self._client) def delete_profile(self, iccid: str) -> None: - if self.is_comma_profile(iccid): + profile = next((p for p in self.list_profiles() if p.iccid == iccid), None) + if profile is None: + raise LPAProfileNotFoundError(f"profile not found: {iccid}") + if profile.is_comma: raise LPAError("refusing to delete a comma profile") with self._acquire_channel(): request = encode_tlv(TAG_DELETE_PROFILE, encode_tlv(TAG_ICCID, string_to_tbcd(iccid))) @@ -788,7 +772,20 @@ class TiciLPA(LPABase): code = self._enable_profile(iccid) if code not in (PROFILE_OK, PROFILE_NOT_IN_DISABLED_STATE): raise LPAError(f"EnableProfile failed: {PROFILE_ERROR_CODES.get(code, 'unknown')} (0x{code:02X})") - from openpilot.system.hardware import HARDWARE - if HARDWARE.get_device_type() == "mici": - self._client.send_raw(b'AT+CFUN=0\rAT+CFUN=1\r') # mici has no SIM presence pin; raw because CFUN=0 drops serial - self._client._ensure_serial(reconnect=True) + + def is_euicc(self) -> bool: + # +CCHO: -> ISD-R applet present, eUICC. Any error -> non-eUICC. + with self._acquire_lock(): + try: + lines = self._client.query(f'AT+CCHO="{ISDR_AID}"') + except RuntimeError: + return False + for line in lines: + if line.startswith("+CCHO:") and (ch := line.split(":", 1)[1].strip()): + try: + self._client.query(f"AT+CCHC={ch}") + except (RuntimeError, TimeoutError): + pass + self._client.channel = None + return True + return False diff --git a/system/hardware/tici/modem.py b/system/hardware/tici/modem.py new file mode 100755 index 0000000000..39266be122 --- /dev/null +++ b/system/hardware/tici/modem.py @@ -0,0 +1,587 @@ +#!/usr/bin/env python3 +import fcntl +import json +import logging +import os +import serial +import signal +import subprocess +import tempfile +import time + +from ipaddress import IPv4Address, AddressValueError + +from enum import Enum + +logging.basicConfig( + level=logging.INFO, + format="%(asctime)s.%(msecs)03d %(levelname)-7s modem: %(message)s", + datefmt="%H:%M:%S", +) + +AT_PORT = "/dev/modem_at0" +PPP_PORT = "/dev/modem_at1" +STATE_PATH = "/dev/shm/modem" +AT_LOCK = "/dev/shm/modem.lock" # shared with LPA +AT_INIT = [ + "ATE0", # disable command echo + "ATV1", # verbose result codes (CONNECT/BUSY/NO CARRIER, not numeric) + "AT+CMEE=1", # numeric +CME ERROR codes on failures (per 3GPP 27.007) + "ATX4", # extended result codes: busy + dial tone detection, line speed in CONNECT + "AT&C1", # DCD pin follows carrier state (V.250 default) + "AT+CREG=2", # registration URCs include location info + "AT+CGREG=2", # GPRS registration URCs include location info +] +CREG = {0: "not_registered", 1: "home", 2: "searching", 3: "denied", 4: "unknown", 5: "roaming"} +# 3GPP TS 27.007 +COPS -> network type +NETWORK_TYPE = {0: "gsm", 1: "gsm", 3: "gsm", 8: "gsm", + 2: "utran", 4: "utran", 5: "utran", 6: "utran", + 7: "lte", 9: "lte", 10: "lte", + 11: "nr", 12: "nr", 13: "nr"} + +DIAL_CID = 1 +WEBBING_ICCID_PREFIX = "8985235" + +PPPD_CMD = [ + "sudo", "pppd", PPP_PORT, "460800", "noauth", "nodetach", "noipdefault", "usepeerdns", + "nodefaultroute", "connect", + "/usr/sbin/chat -v ABORT 'NO CARRIER' ABORT 'NO DIALTONE' ABORT 'BUSY' " + + f"ABORT 'NO ANSWER' ABORT 'ERROR' TIMEOUT 5 '' AT OK ATD*99***{DIAL_CID}# CONNECT ''", + "lcp-echo-interval", "30", "lcp-echo-failure", "4", "mtu", "1500", "mru", "1500", + "novj", "novjccomp", "ipcp-accept-local", "ipcp-accept-remote", "nomagic", + "user", '""', "password", '""', +] +INITIAL_STATE = { + "seconds_since_boot": 0, + "state": "INITIALIZING", + "connected": False, "ip_address": "", + "iccid": "", "mcc_mnc": "", "imei": "", "modem_version": "", + "signal_strength": 0, "signal_quality": 0, + "network_type": "unknown", "operator": "", "band": "", "channel": 0, + "registration": "unknown", "temperatures": [], "extra": "", + "tx_bytes": 0, "rx_bytes": 0, +} + + +class State(Enum): + INITIALIZING = "INITIALIZING" + SEARCHING = "SEARCHING" + CONNECTING = "CONNECTING" + CONNECTED = "CONNECTED" + DISCONNECTING = "DISCONNECTING" + + +STATE_WAIT = 1.0 # seconds to wait after each state handler returns + + +class PPPSession: + """Owns pppd lifecycle, fail tracking, and PPP routing.""" + MAX_FAILS = 3 + + def __init__(self): + self._proc: subprocess.Popen | None = None + self._fails = 0 + self._peer = "" + + def start(self): + self._proc = subprocess.Popen(PPPD_CMD, stdout=subprocess.DEVNULL, stderr=subprocess.DEVNULL) + self._peer = "" + logging.info(f"PPP dialing CID {DIAL_CID}") + + def kill(self): + subprocess.run(["sudo", "killall", "-9", "pppd"], capture_output=True) + self._peer = "" + + @staticmethod + def reset_data_port(): + """Drop DTR on PPP_PORT so the modem terminates any stuck PPP session.""" + try: + with serial.Serial(PPP_PORT, 460800, timeout=1) as s: + s.dtr = False + time.sleep(0.2) + s.dtr = True + except Exception as e: + logging.warning(f"data port reset failed: {e}") + + def has_exited(self) -> bool: + return self._proc is not None and self._proc.poll() is not None + + def reset_fail_counter(self): + self._fails = 0 + + def record_fail(self) -> bool: + """Bump fail counter; return True if at the give-up limit.""" + self._fails += 1 + return self._fails >= self.MAX_FAILS + + @property + def fails(self) -> int: + return self._fails + + def maybe_install_routes(self, ip: str, peer: str) -> bool: + """Install routes if peer changed; kill the session on failure so the state machine reconnects.""" + if not peer or peer == self._peer: + return False + try: + IPv4Address(ip) + IPv4Address(peer) + except AddressValueError: + logging.warning(f"refusing route install with non-IPv4 ip={ip!r} peer={peer!r}") + self.kill() + return False + self.cleanup_routes() + cmds = [ + ["sudo", "ip", "route", "add", "default", "via", peer, "dev", "ppp0", "metric", "1000"], + ["sudo", "ip", "route", "add", "default", "via", peer, "dev", "ppp0", "table", "1000"], + ["sudo", "ip", "rule", "add", "from", ip, "table", "1000"], + ] + for cmd in cmds: + r = subprocess.run(cmd, capture_output=True, text=True) + if r.returncode != 0: + logging.warning(f"route install failed ({' '.join(cmd[1:])}): {r.stderr.strip()}") + self.cleanup_routes() + self.kill() + return False + logging.info(f"route set up for {ip} via {peer}") + self._peer = peer + return True + + def maybe_install_dns(self, dns_servers: list[str]) -> bool: + """Register DNS servers with systemd-resolved; kill the session on failure to force a retry.""" + if not dns_servers: + return False + for cmd in (["sudo", "resolvectl", "dns", "ppp0", *dns_servers], + ["sudo", "resolvectl", "default-route", "ppp0", "yes"]): + r = subprocess.run(cmd, capture_output=True, text=True) + if r.returncode != 0: + logging.warning(f"resolvectl failed ({' '.join(cmd[1:])}): {r.stderr.strip()}") + self.kill() + return False + logging.info(f"resolvectl: ppp0 DNS = {dns_servers}") + return True + + @staticmethod + def cleanup_routes(): + subprocess.run(["sudo", "ip", "route", "del", "default", "dev", "ppp0"], capture_output=True) + subprocess.run(["sudo", "ip", "route", "flush", "table", "1000"], capture_output=True) + # rules don't have a flush; delete until none remain + while subprocess.run(["sudo", "ip", "rule", "del", "table", "1000"], capture_output=True).returncode == 0: + pass + subprocess.run(["sudo", "resolvectl", "revert", "ppp0"], capture_output=True) + + +class Modem: + def __init__(self): + self._ppp = PPPSession() + self._sim_change = False + self._apn = "" # blank = network-provided via PCO + self._roaming_allowed = True + self.running = True + self.S = INITIAL_STATE.copy() + + @staticmethod + def _read_param(key): + try: + with open(f"/data/params/d/{key}") as f: + return f.read().strip() + except FileNotFoundError: + return "" + + @staticmethod + def _parse_reg(v: str) -> str: + try: + return CREG.get(int(v.split(",")[1].strip('"')), "unknown") + except (ValueError, IndexError): + return "unknown" + + @staticmethod + def _has_modem_manager() -> bool: + return os.path.isfile("/lib/systemd/system/ModemManager.service") + + def _is_roaming_allowed(self) -> bool: + if self.S["iccid"].startswith(WEBBING_ICCID_PREFIX): + return True + return self._read_param("GsmRoaming") == "1" + + def _publish_state(self, **kwargs): + self.S.update(kwargs) + self.S["seconds_since_boot"] = time.monotonic() + with tempfile.NamedTemporaryFile(mode="w", dir="/dev/shm", delete=False) as f: + json.dump(self.S, f, indent=2) + os.chmod(f.name, 0o644) + os.replace(f.name, STATE_PATH) + + def _at(self, cmd): + """Send AT command, return response lines. [] on error or if LPA holds port.""" + fd = os.open(AT_LOCK, os.O_CREAT | os.O_RDWR, 0o666) + try: + fcntl.flock(fd, fcntl.LOCK_EX | fcntl.LOCK_NB) + except OSError: + os.close(fd) + return [] + try: + with serial.Serial(AT_PORT, 9600, timeout=5) as ser: + ser.reset_input_buffer() + ser.write((cmd + "\r").encode()) + lines = [] + while True: + raw = ser.readline() + if not raw: + raise TimeoutError("AT timeout") + line = raw.decode(errors="ignore").strip() + if not line: + continue + if line == "OK": + break + if line == "ERROR" or line.startswith("+CME ERROR"): + raise RuntimeError(line) + lines.append(line) + return lines + except (RuntimeError, TimeoutError, OSError) as e: + logging.info(f"AT {cmd} failed: {e}") + return [] + finally: + fcntl.flock(fd, fcntl.LOCK_UN) + os.close(fd) + + def _atv(self, cmd, pfx): + for line in self._at(cmd): + if pfx in line and ":" in line: + return line.split(":", 1)[1].strip() + return None + + def _init_at_channel(self) -> bool: + """Run AT_INIT and confirm ATE0 took effect. Returns False if echo is still on.""" + for c in AT_INIT: + self._at(c) + r = self._at("AT+CGMI") + return bool(r) and not r[0].startswith("AT") + + def _configure_modem(self, modem_version: str): + if not modem_version.startswith("EG25"): + return + cmds = [ + # clear initial EPS bearer APN (some carriers reject the default) + 'AT+CGDCONT=0,"IP",""', + + # SIM hot swap + 'AT+QSIMDET=1,0', + 'AT+QSIMSTAT=1', + + # configure modem as data-centric + 'AT+QNVW=5280,0,"0102000000000000"', + 'AT+QNVFW="/nv/item_files/ims/IMS_enable",00', + 'AT+QNVFW="/nv/item_files/modem/mmode/ue_usage_setting",01', + ] + for c in cmds: + self._at(c) + + def _do_initializing(self): + if not os.path.exists(AT_PORT): + return State.INITIALIZING + logging.info("port found, initializing") + self._ppp.kill() + self._ppp.cleanup_routes() + + if not self._init_at_channel(): + logging.warning("AT echo still on, retrying") + return State.INITIALIZING + + identity = self._read_identity() + if not identity["iccid"] or not identity["imei"]: + logging.warning(f"identity read incomplete: {identity}, retrying") + return State.INITIALIZING + + self._configure_modem(identity["modem_version"]) + + self.S.update(identity) + self._apn = self._read_param("GsmApn") + self._roaming_allowed = self._is_roaming_allowed() + # blank APN lets the carrier supply one via PCO + self._at(f'AT+CGDCONT={DIAL_CID},"IP","{self._apn}"') + logging.info(f"APN '{self._apn or '(network-provided)'}' written to CID {DIAL_CID}, roaming={'on' if self._roaming_allowed else 'off'}") + + self._sim_change = False # clear since we just re-read identity with the new SIM + self._publish_state(**identity) + return State.SEARCHING + + def _read_identity(self): + def first_line(cmd): + r = self._at(cmd) + return r[0].strip() if r else "" + + imei = first_line("AT+CGSN") + if not (imei.isdigit() and 14 <= len(imei) <= 17): # 3GPP TS 23.003 + imei = "" + + iccid = (self._atv("AT+QCCID", "+QCCID:") or "").rstrip("F") + if not iccid.isdigit(): + iccid = "" + + imsi = first_line("AT+CIMI") + mcc_mnc = imsi[:6] if imsi.isdigit() and len(imsi) >= 6 else "" + + modem_version = first_line("AT+GMR") + + logging.info(f"imei={imei} iccid={iccid} mcc_mnc={mcc_mnc} ver={modem_version}") + return {"imei": imei, "iccid": iccid, "mcc_mnc": mcc_mnc, "modem_version": modem_version} + + def _do_searching(self): + new_roaming = self._is_roaming_allowed() + if new_roaming != self._roaming_allowed: + logging.info(f"roaming changed: {self._roaming_allowed} -> {new_roaming}") + self._roaming_allowed = new_roaming + + v = self._atv("AT+CREG?", "+CREG:") + if not v: + return self._searching_idle() + + reg = self._parse_reg(v) + greg = self._parse_reg(self._atv("AT+CGREG?", "+CGREG:") or "") + logging.debug(f"creg={reg} cgreg={greg} roaming_allowed={self._roaming_allowed}") + + if reg == "roaming" and not self._roaming_allowed: + self._publish_state(registration=reg) + return State.SEARCHING + + if reg in ("home", "roaming") and greg in ("home", "roaming"): + self._publish_state(registration=reg) + return State.CONNECTING + + if reg != self.S.get("registration"): + self._publish_state(registration=reg) + return self._searching_idle() + + def _searching_idle(self): + if self._sim_change or not os.path.exists(AT_PORT): + logging.info(f"-> reconnecting (sim_change={self._sim_change} port={os.path.exists(AT_PORT)})") + return State.DISCONNECTING + return State.SEARCHING + + def _do_connecting(self): + logging.info("starting pppd") + self._ppp.reset_fail_counter() + self._sim_change = False + self._ppp.start() + return State.CONNECTED + + def _handle_pppd_exit(self): + if self._sim_change or not os.path.exists(AT_PORT): + return State.DISCONNECTING + give_up = self._ppp.record_fail() + if give_up: + logging.warning(f"PPP fail {self._ppp.fails}/{self._ppp.MAX_FAILS}, reconnecting") + return State.DISCONNECTING + logging.warning(f"PPP fail {self._ppp.fails}/{self._ppp.MAX_FAILS}, retrying") + self._ppp.reset_data_port() + if not os.path.exists(AT_PORT): + return State.DISCONNECTING + self._ppp.start() + return State.CONNECTED + + def _params_changed(self) -> bool: + new_apn = self._read_param("GsmApn") + if new_apn != self._apn: + logging.info(f"GsmApn changed: '{self._apn}' -> '{new_apn}'") + return True + new_roaming = self._is_roaming_allowed() + if new_roaming != self._roaming_allowed: + logging.info(f"roaming changed: {self._roaming_allowed} -> {new_roaming}") + return True + return False + + def _check_iccid(self, state): + if state in (State.INITIALIZING, State.DISCONNECTING) or not self.S["iccid"]: + return + iccid = (self._atv("AT+QCCID", "+QCCID:") or "").rstrip("F") + if iccid and iccid != self.S["iccid"]: + logging.warning(f"iccid changed: {self.S['iccid']} -> {iccid}") + self._sim_change = True + + def _do_connected(self): + if self._ppp.has_exited(): + return self._handle_pppd_exit() + + if self._sim_change or not os.path.exists(AT_PORT) or self._params_changed(): + return State.DISCONNECTING + + self._poll() + return State.CONNECTED + + def _do_disconnecting(self): + logging.warning("reconnecting") + self._publish_state(**INITIAL_STATE) + self._ppp.kill() + self._ppp.cleanup_routes() + self._ppp.reset_data_port() + self._sim_change = False + return State.INITIALIZING + + def _poll_signal(self) -> dict: + v = self._atv("AT+CSQ", "+CSQ:") + if not v: + return {} + try: + rssi = int(v.split(",")[0]) + if rssi == 99: + return {} + return {"signal_strength": rssi, "signal_quality": min(100, int(rssi / 31 * 100))} + except (ValueError, IndexError): + return {} + + def _poll_operator(self) -> dict: + v = self._atv("AT+COPS?", "+COPS:") + if not v: + return {} + p = v.split(",") + out: dict = {} + try: + if len(p) >= 3: + out["operator"] = p[2].strip('"') + if len(p) >= 4: + out["network_type"] = NETWORK_TYPE.get(int(p[3]), "unknown") + except (ValueError, IndexError): + pass + return out + + def _poll_band(self) -> dict: + v = self._atv("AT+QNWINFO", "+QNWINFO:") + if not v: + return {} + info = v.replace('"', '').split(",") + try: + if len(info) >= 4: + return {"band": info[2], "channel": int(info[3])} + except ValueError: + pass + return {} + + def _poll_extra(self) -> dict: + v = self._atv('AT+QENG="servingcell"', "+QENG:") + return {"extra": v.replace('"', '')} if v else {} + + def _poll_temps(self) -> dict: + v = self._atv("AT+QTEMP", "+QTEMP:") + if not v: + return {} + try: + return {"temperatures": [t for t in (int(x) for x in v.split(",") if x.strip()) if t != 255]} + except (ValueError, IndexError): + return {} + + def _poll_iface(self) -> dict: + try: + r = subprocess.run(["ip", "-4", "addr", "show", "ppp0"], capture_output=True, text=True, timeout=2) + ip, peer = "", "" + for line in r.stdout.splitlines(): + # `inet 10.x.x.x peer 10.64.64.64/32 ...` + parts = line.strip().split() + if "inet" in parts: + i = parts.index("inet") + ip = parts[i + 1].split("/")[0] + if "peer" in parts: + peer = parts[parts.index("peer") + 1].split("/")[0] + break + if ip: + if self._ppp.maybe_install_routes(ip, peer): + self._ppp.maybe_install_dns(self._read_cellular_dns()) + return {"ip_address": ip, "connected": True} + if self.S["connected"]: + return {"connected": False, "ip_address": ""} + except Exception: + pass + return {} + + def _read_cellular_dns(self) -> list[str]: + v = self._atv(f"AT+CGCONTRDP={DIAL_CID}", "+CGCONTRDP:") + if not v: + return [] + # +CGCONTRDP: ,,,,,,,... + fields = [f.strip().strip('"') for f in v.split(",")] + dns_servers = [] + for d in fields[5:7]: + try: + dns_servers.append(str(IPv4Address(d))) + except (AddressValueError, ValueError): + pass + if not dns_servers: + logging.warning(f"no cellular DNS servers reported by modem: {v!r}") + return dns_servers + + def _poll_byte_counters(self) -> dict: + try: + with open("/sys/class/net/ppp0/statistics/tx_bytes") as f: + tx = int(f.read().strip()) + with open("/sys/class/net/ppp0/statistics/rx_bytes") as f: + rx = int(f.read().strip()) + except Exception: + return {} + return {"tx_bytes": tx, "rx_bytes": rx} + + def _poll(self): + s: dict = {} + for fn in (self._poll_signal, self._poll_operator, self._poll_band, + self._poll_extra, self._poll_temps, self._poll_iface, + self._poll_byte_counters): + s.update(fn()) + if s: + self._publish_state(**s) + + def run(self): + logging.info("starting") + self._publish_state(state=State.INITIALIZING.value) + if self._has_modem_manager(): + subprocess.run(["sudo", "systemctl", "mask", "--runtime", "ModemManager"], capture_output=True) + subprocess.run(["sudo", "systemctl", "stop", "ModemManager"], capture_output=True) + self._ppp.kill() + + state = State.INITIALIZING + + handlers = { + State.INITIALIZING: self._do_initializing, + State.SEARCHING: self._do_searching, + State.CONNECTING: self._do_connecting, + State.CONNECTED: self._do_connected, + State.DISCONNECTING: self._do_disconnecting, + } + + while self.running: + try: + self._check_iccid(state) + prev = state + state = handlers[state]() + if state != prev: + self._publish_state(state=state.value) + logging.info(f"{prev.value} -> {state.value}") + except Exception: + logging.exception(f"error in {state.value}") + state = State.DISCONNECTING + time.sleep(STATE_WAIT) + + def stop(self): + self.running = False + self._ppp.kill() + self._ppp.cleanup_routes() + try: + os.remove(STATE_PATH) + except FileNotFoundError: + pass + if self._has_modem_manager(): + subprocess.run(["sudo", "systemctl", "unmask", "--runtime", "ModemManager"], capture_output=True) + subprocess.run(["sudo", "systemctl", "start", "ModemManager"], capture_output=True) + + +def main(): + m = Modem() + + def _sig(*_): + m.running = False + + signal.signal(signal.SIGINT, _sig) + signal.signal(signal.SIGTERM, _sig) + m.run() + m.stop() + + +if __name__ == "__main__": + main() diff --git a/system/hardware/tici/restart_modem.sh b/system/hardware/tici/restart_modem.sh deleted file mode 100755 index 741dc72050..0000000000 --- a/system/hardware/tici/restart_modem.sh +++ /dev/null @@ -1,18 +0,0 @@ -#!/usr/bin/env bash - -#nmcli connection modify --temporary lte gsm.home-only yes -#nmcli connection modify --temporary lte gsm.auto-config yes -#nmcli connection modify --temporary lte connection.autoconnect-retries 20 -sudo nmcli connection reload - -sudo systemctl stop ModemManager -nmcli con down lte -nmcli con down blue-prime - -# power cycle modem -/usr/comma/lte/lte.sh stop_blocking -/usr/comma/lte/lte.sh start - -sudo systemctl restart NetworkManager -#sudo systemctl restart ModemManager -sudo ModemManager --debug diff --git a/system/hardware/tici/tests/test_power_draw.py b/system/hardware/tici/tests/test_power_draw.py index c4401c9583..6656addf73 100644 --- a/system/hardware/tici/tests/test_power_draw.py +++ b/system/hardware/tici/tests/test_power_draw.py @@ -42,7 +42,7 @@ PROCS = [ class TestPowerDraw: def setup_method(self): - Params().put("CarParams", get_demo_car_params().to_bytes()) + Params().put("CarParams", get_demo_car_params().to_bytes(), block=True) # wait a bit for power save to disable time.sleep(5) diff --git a/system/hardware/tici/updater b/system/hardware/tici/updater index 69ce323a10..44b82d0c54 100755 --- a/system/hardware/tici/updater +++ b/system/hardware/tici/updater @@ -1,17 +1,3 @@ -#!/usr/bin/env bash - -DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )" - -AGNOS_PY=$1 -MANIFEST=$2 - -if [[ ! -f "$AGNOS_PY" || ! -f "$MANIFEST" ]]; then - echo "invalid args" - exit 1 -fi - -if systemctl is-active --quiet weston-ready; then - $DIR/updater_weston $AGNOS_PY $MANIFEST -else - $DIR/updater_magic $AGNOS_PY $MANIFEST -fi +version https://git-lfs.github.com/spec/v1 +oid sha256:3a94ab8395f20d20a9d5a2a2bacca0694f072df8421cf13adca6250d28065bdc +size 24709205 diff --git a/system/hardware/tici/updater_magic b/system/hardware/tici/updater_magic deleted file mode 100755 index 44b82d0c54..0000000000 --- a/system/hardware/tici/updater_magic +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:3a94ab8395f20d20a9d5a2a2bacca0694f072df8421cf13adca6250d28065bdc -size 24709205 diff --git a/system/hardware/tici/updater_weston b/system/hardware/tici/updater_weston deleted file mode 100755 index 23cdc140f4..0000000000 --- a/system/hardware/tici/updater_weston +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:eba5f44e6a763e1f74d1c718993218adcc72cba4caafe99b595fa701151a4c54 -size 10448792 diff --git a/system/loggerd/SConscript b/system/loggerd/SConscript index 45e8b25d20..a638704dca 100644 --- a/system/loggerd/SConscript +++ b/system/loggerd/SConscript @@ -5,18 +5,17 @@ libs = [common, messaging, visionipc, 'pthread', 'z', 'm', 'zstd'] frameworks = [] -src = ['logger.cc', 'zstd_writer.cc', 'video_writer.cc', 'encoder/encoder.cc', 'encoder/v4l_encoder.cc', 'encoder/jpeg_encoder.cc'] -if arch != "larch64": +src = ['logger.cc', 'zstd_writer.cc', 'video_writer.cc', 'encoder/encoder.cc', 'encoder/jpeg_encoder.cc'] +if arch == "larch64": + src += ['encoder/v4l_encoder.cc'] +else: src += ['encoder/ffmpeg_encoder.cc'] libs += ['yuv'] if arch == "Darwin": frameworks += ['VideoToolbox', 'CoreMedia', 'CoreFoundation', 'CoreVideo'] - else: - libs += ['va', 'va-drm', 'drm'] -if arch == "Darwin": - # exclude v4l - del src[src.index('encoder/v4l_encoder.cc')] +if arch != "Darwin": + libs += ['va', 'va-drm', 'drm'] logger_lib = env.Library('logger', src) libs.insert(0, logger_lib) diff --git a/system/loggerd/encoder/encoder.h b/system/loggerd/encoder/encoder.h index 57146fafc3..0a136f769c 100644 --- a/system/loggerd/encoder/encoder.h +++ b/system/loggerd/encoder/encoder.h @@ -2,7 +2,7 @@ // has to be in this order #ifdef __linux__ -#include "third_party/linux/include/v4l2-controls.h" +#include #include #else #define V4L2_BUF_FLAG_KEYFRAME 8 @@ -26,6 +26,7 @@ public: virtual int encode_frame(VisionBuf* buf, VisionIpcBufExtra *extra) = 0; virtual void encoder_open() = 0; virtual void encoder_close() = 0; + virtual void set_bitrate(int bitrate) = 0; void publisher_publish(int segment_num, uint32_t idx, VisionIpcBufExtra &extra, unsigned int flags, kj::ArrayPtr header, kj::ArrayPtr dat); diff --git a/system/loggerd/encoder/ffmpeg_encoder.cc b/system/loggerd/encoder/ffmpeg_encoder.cc index 275a2e481e..f6399659b4 100644 --- a/system/loggerd/encoder/ffmpeg_encoder.cc +++ b/system/loggerd/encoder/ffmpeg_encoder.cc @@ -72,6 +72,10 @@ void FfmpegEncoder::encoder_close() { is_open = false; } +void FfmpegEncoder::set_bitrate(int bitrate) { + LOGE("adaptive bitrate is not supported for ffmpeg encoder %s", encoder_info.publish_name); +} + int FfmpegEncoder::encode_frame(VisionBuf* buf, VisionIpcBufExtra *extra) { assert(buf->width == this->in_width); assert(buf->height == this->in_height); diff --git a/system/loggerd/encoder/ffmpeg_encoder.h b/system/loggerd/encoder/ffmpeg_encoder.h index cd5ac1e13a..a85e1d3816 100644 --- a/system/loggerd/encoder/ffmpeg_encoder.h +++ b/system/loggerd/encoder/ffmpeg_encoder.h @@ -21,6 +21,7 @@ public: int encode_frame(VisionBuf* buf, VisionIpcBufExtra *extra); void encoder_open(); void encoder_close(); + void set_bitrate(int bitrate); private: int segment_num = -1; diff --git a/system/loggerd/encoder/v4l_encoder.cc b/system/loggerd/encoder/v4l_encoder.cc index cabd9fd997..96a565f4ae 100644 --- a/system/loggerd/encoder/v4l_encoder.cc +++ b/system/loggerd/encoder/v4l_encoder.cc @@ -7,10 +7,10 @@ #include "common/util.h" #include "common/timing.h" -#include "third_party/linux/include/msm_media_info.h" +#include // has to be in this order -#include "third_party/linux/include/v4l2-controls.h" +#include #include #define V4L2_QCOM_BUF_FLAG_CODECCONFIG 0x00020000 #define V4L2_QCOM_BUF_FLAG_EOS 0x02000000 @@ -155,6 +155,8 @@ V4LEncoder::V4LEncoder(const EncoderInfo &encoder_info, int in_width, int in_hei assert(strcmp((const char *)cap.card, "msm_vidc_venc") == 0); EncoderSettings encoder_settings = encoder_info.get_settings(in_width); + current_bitrate = encoder_settings.bitrate; + adaptive_bitrate = encoder_info.adaptive_bitrate; bool is_h265 = encoder_settings.encode_type == cereal::EncodeIndex::Type::FULL_H_E_V_C; struct v4l2_format fmt_out = { @@ -304,6 +306,25 @@ void V4LEncoder::encoder_close() { this->is_open = false; } +void V4LEncoder::set_bitrate(int bitrate) { + if (!adaptive_bitrate || bitrate == current_bitrate) return; + if (bitrate <= 0) { + LOGE("invalid livestream encoder bitrate %d", bitrate); + return; + } + + struct v4l2_control ctrl = { + .id = V4L2_CID_MPEG_VIDEO_BITRATE, + .value = bitrate, + }; + + if (util::safe_ioctl(fd, VIDIOC_S_CTRL, &ctrl) == -1) { + LOGE("failed to update %s bitrate to %d", encoder_info.publish_name, bitrate); + return; + } + current_bitrate = bitrate; +} + V4LEncoder::~V4LEncoder() { encoder_close(); v4l2_buf_type buf_type = V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE; diff --git a/system/loggerd/encoder/v4l_encoder.h b/system/loggerd/encoder/v4l_encoder.h index 58011d60e1..2985409605 100644 --- a/system/loggerd/encoder/v4l_encoder.h +++ b/system/loggerd/encoder/v4l_encoder.h @@ -13,6 +13,7 @@ public: int encode_frame(VisionBuf* buf, VisionIpcBufExtra *extra); void encoder_open(); void encoder_close(); + void set_bitrate(int bitrate); private: int fd; @@ -20,6 +21,8 @@ private: bool is_open = false; int segment_num = -1; int counter = 0; + int current_bitrate = -1; + bool adaptive_bitrate; SafeQueue extras; diff --git a/system/loggerd/encoderd.cc b/system/loggerd/encoderd.cc index 9d4b81a3f9..546990041a 100644 --- a/system/loggerd/encoderd.cc +++ b/system/loggerd/encoderd.cc @@ -44,11 +44,24 @@ bool sync_encoders(EncoderdState *s, VisionStreamType cam_type, uint32_t frame_i } } +void apply_bitrate(std::vector> &encoders) { + static Params params; + std::string val = params.get("LivestreamEncoderBitrate"); + if (val.empty()) return; + int bitrate = std::stoi(val); + for (auto &e : encoders) { + e->set_bitrate(bitrate); + } +} void encoder_thread(EncoderdState *s, const LogCameraInfo &cam_info) { util::set_thread_name(cam_info.thread_name); std::vector> encoders; + + bool has_adaptive = std::any_of(cam_info.encoder_infos.begin(), cam_info.encoder_infos.end(), + [](const auto &ei) { return ei.adaptive_bitrate; }); + VisionIpcClient vipc_client = VisionIpcClient("camerad", cam_info.stream_type, false); std::unique_ptr jpeg_encoder; @@ -108,6 +121,8 @@ void encoder_thread(EncoderdState *s, const LogCameraInfo &cam_info) { ++cur_seg; } + if (has_adaptive) apply_bitrate(encoders); + // encode a frame for (int i = 0; i < encoders.size(); ++i) { int out_id = encoders[i]->encode_frame(buf, &extra); diff --git a/system/loggerd/loggerd.h b/system/loggerd/loggerd.h index 6aa0c8be40..340e72e6fd 100644 --- a/system/loggerd/loggerd.h +++ b/system/loggerd/loggerd.h @@ -47,8 +47,8 @@ struct EncoderSettings { } static EncoderSettings StreamEncoderSettings() { - int _stream_bitrate = getenv("STREAM_BITRATE") ? atoi(getenv("STREAM_BITRATE")) : 1'000'000; - return EncoderSettings{.encode_type = cereal::EncodeIndex::Type::QCAMERA_H264, .bitrate = _stream_bitrate , .gop_size = 15}; + int _stream_bitrate = getenv("STREAM_BITRATE") ? atoi(getenv("STREAM_BITRATE")) : 5'000'000; + return EncoderSettings{.encode_type = cereal::EncodeIndex::Type::QCAMERA_H264, .bitrate = _stream_bitrate , .gop_size = 5}; } }; @@ -59,6 +59,7 @@ public: const char *filename = NULL; bool record = true; bool include_audio = false; + bool adaptive_bitrate = false; int frame_width = -1; int frame_height = -1; int fps = MAIN_FPS; @@ -104,6 +105,7 @@ const EncoderInfo stream_road_encoder_info = { .publish_name = "livestreamRoadEncodeData", //.thumbnail_name = "thumbnail", .record = false, + .adaptive_bitrate = true, .get_settings = [](int){return EncoderSettings::StreamEncoderSettings();}, INIT_ENCODE_FUNCTIONS(LivestreamRoadEncode), }; @@ -111,6 +113,7 @@ const EncoderInfo stream_road_encoder_info = { const EncoderInfo stream_wide_road_encoder_info = { .publish_name = "livestreamWideRoadEncodeData", .record = false, + .adaptive_bitrate = true, .get_settings = [](int){return EncoderSettings::StreamEncoderSettings();}, INIT_ENCODE_FUNCTIONS(LivestreamWideRoadEncode), }; @@ -118,6 +121,7 @@ const EncoderInfo stream_wide_road_encoder_info = { const EncoderInfo stream_driver_encoder_info = { .publish_name = "livestreamDriverEncodeData", .record = false, + .adaptive_bitrate = true, .get_settings = [](int){return EncoderSettings::StreamEncoderSettings();}, INIT_ENCODE_FUNCTIONS(LivestreamDriverEncode), }; @@ -153,19 +157,19 @@ const LogCameraInfo driver_camera_info{ const LogCameraInfo stream_road_camera_info{ .thread_name = "road_cam_encoder", .stream_type = VISION_STREAM_ROAD, - .encoder_infos = {stream_road_encoder_info} + .encoder_infos = {stream_road_encoder_info}, }; const LogCameraInfo stream_wide_road_camera_info{ .thread_name = "wide_road_cam_encoder", .stream_type = VISION_STREAM_WIDE_ROAD, - .encoder_infos = {stream_wide_road_encoder_info} + .encoder_infos = {stream_wide_road_encoder_info}, }; const LogCameraInfo stream_driver_camera_info{ .thread_name = "driver_cam_encoder", .stream_type = VISION_STREAM_DRIVER, - .encoder_infos = {stream_driver_encoder_info} + .encoder_infos = {stream_driver_encoder_info}, }; const LogCameraInfo cameras_logged[] = {road_camera_info, wide_road_camera_info, driver_camera_info}; diff --git a/system/loggerd/tests/loggerd_tests_common.py b/system/loggerd/tests/loggerd_tests_common.py index 8bf609ae8d..fd071486df 100644 --- a/system/loggerd/tests/loggerd_tests_common.py +++ b/system/loggerd/tests/loggerd_tests_common.py @@ -76,8 +76,8 @@ class UploaderTestCase: self.seg_dir = self.seg_format.format(self.seg_num) self.params = Params() - self.params.put("IsOffroad", True) - self.params.put("DongleId", "0000000000000000") + self.params.put("IsOffroad", True, block=True) + self.params.put("DongleId", "0000000000000000", block=True) def make_file_with_data(self, f_dir: str, fn: str, size_mb: float = .1, lock: bool = False, upload_xattr: bytes | None = None, preserve_xattr: bytes | None = None) -> Path: diff --git a/system/loggerd/tests/test_encoder.py b/system/loggerd/tests/test_encoder.py index a9de0690aa..2b74fe2276 100644 --- a/system/loggerd/tests/test_encoder.py +++ b/system/loggerd/tests/test_encoder.py @@ -53,7 +53,7 @@ class TestEncoder: # TODO: this should run faster than real time @parameterized.expand([(True, ), (False, )]) def test_log_rotation(self, record_front): - Params().put_bool("RecordFront", record_front) + Params().put_bool("RecordFront", record_front, block=True) managed_processes['sensord'].start() managed_processes['loggerd'].start() diff --git a/system/loggerd/tests/test_loggerd.py b/system/loggerd/tests/test_loggerd.py index 9703ac2f5f..9fd1b2d434 100644 --- a/system/loggerd/tests/test_loggerd.py +++ b/system/loggerd/tests/test_loggerd.py @@ -82,7 +82,7 @@ class TestLoggerd: assert pm.wait_for_readers_to_update(s, timeout=5) sent_msgs = defaultdict(list) - for _ in range(random.randint(2, 10) * 100): + for i in range(random.randint(2, 10) * 100): for s in services: try: m = messaging.new_message(s) @@ -91,6 +91,12 @@ class TestLoggerd: pm.send(s, m) sent_msgs[s].append(m) + # Keep msgq's finite per-service queues from wrapping; this test asserts + # that loggerd logged every message we sent. + if (i + 1) % 100 == 0: + for s in services: + assert pm.wait_for_readers_to_update(s, timeout=5) + for s in services: assert pm.wait_for_readers_to_update(s, timeout=5) managed_processes["loggerd"].stop() @@ -161,8 +167,8 @@ class TestLoggerd: ] params = Params() for k, _, v in fake_params: - params.put(k, v) - params.put("AccessToken", "abc") + params.put(k, v, block=True) + params.put("AccessToken", "abc", block=True) lr = list(LogReader(str(self._gen_bootlog()))) initData = lr[0].initData @@ -188,7 +194,7 @@ class TestLoggerd: @pytest.mark.xdist_group("camera_encoder_tests") # setting xdist group ensures tests are run in same worker, prevents encoderd from crashing def test_rotation(self): - Params().put("RecordFront", True) + Params().put("RecordFront", True, block=True) expected_files = {"rlog.zst", "qlog.zst", "qcamera.ts", "fcamera.hevc", "dcamera.hevc", "ecamera.hevc"} @@ -309,7 +315,7 @@ class TestLoggerd: @pytest.mark.parametrize("record_front", [True, False]) def test_record_front(self, record_front): params = Params() - params.put_bool("RecordFront", record_front) + params.put_bool("RecordFront", record_front, block=True) self._publish_camera_and_audio_messages() @@ -320,7 +326,7 @@ class TestLoggerd: @pytest.mark.parametrize("record_audio", [True, False]) def test_record_audio(self, record_audio): params = Params() - params.put_bool("RecordAudio", record_audio) + params.put_bool("RecordAudio", record_audio, block=True) self._publish_camera_and_audio_messages() diff --git a/system/manager/build.py b/system/manager/build.py index d79e7fd2ad..470cfccdaa 100755 --- a/system/manager/build.py +++ b/system/manager/build.py @@ -1,73 +1,58 @@ #!/usr/bin/env python3 import os import subprocess -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.common.swaglog import cloudlog, add_file_handler from openpilot.system.hardware import HARDWARE, AGNOS -from openpilot.system.version import get_build_metadata -MAX_CACHE_SIZE = 4e9 if "CI" in os.environ else 2e9 -CACHE_DIR = Path("/data/scons_cache" if AGNOS else "/tmp/scons_cache") - -TOTAL_SCONS_NODES = 2705 -MAX_BUILD_PROGRESS = 100 - -def build(spinner: Spinner, dirty: bool = False, minimal: bool = False) -> None: - env = os.environ.copy() - env['SCONS_PROGRESS'] = "1" - nproc = os.cpu_count() - if nproc is None: - nproc = 2 - - extra_args = ["--minimal"] if minimal else [] +def build() -> None: + spinner = Spinner() + spinner.update_progress(0, 100) + HARDWARE.set_power_save(False) if AGNOS: - HARDWARE.set_power_save(False) os.sched_setaffinity(0, range(8)) # ensure we can use the isolcpus cores - # building with all cores can result in using too - # much memory, so retry with less parallelism + # building with all cores can result in using too much memory, so retry serially compile_output: list[bytes] = [] - for n in (nproc, nproc/2, 1): + for parallelism in ([], ["-j4"], ["-j1"]): compile_output.clear() - scons: subprocess.Popen = subprocess.Popen(["scons", f"-j{int(n)}", "--cache-populate", *extra_args], cwd=BASEDIR, env=env, stderr=subprocess.PIPE) - assert scons.stderr is not None + with subprocess.Popen(["scons", *parallelism], cwd=BASEDIR, env={**os.environ, "PWD": BASEDIR}, stderr=subprocess.PIPE) as scons: + assert scons.stderr is not None - # Read progress from stderr and update spinner - while scons.poll() is None: - try: - line = scons.stderr.readline() - if line is None: - continue + # Read progress from stderr and update spinner + while scons.poll() is None: + try: + line = scons.stderr.readline() + if line is None: + continue + line = line.rstrip() + + prefix = b'progress: ' + if line.startswith(prefix): + progress = float(line[len(prefix):]) + spinner.update_progress(100 * min(1., progress / 100.), 100.) + elif len(line): + compile_output.append(line) + print(line.decode('utf8', 'replace')) + except Exception: + pass + + # Drain and close the pipe before retrying or returning. + for line in scons.stderr.read().split(b'\n'): line = line.rstrip() - - prefix = b'progress: ' - if line.startswith(prefix): - i = int(line[len(prefix):]) - spinner.update_progress(MAX_BUILD_PROGRESS * min(1., i / TOTAL_SCONS_NODES), 100.) - elif len(line): + if len(line): compile_output.append(line) - print(line.decode('utf8', 'replace')) - except Exception: - pass if scons.returncode == 0: break if scons.returncode != 0: - # Read remaining output - if scons.stderr is not None: - compile_output += scons.stderr.read().split(b'\n') - # Build failed log errors error_s = b"\n".join(compile_output).decode('utf8', 'replace') - add_file_handler(cloudlog) - cloudlog.error("scons build failed\n" + error_s) # Show TextWindow spinner.close() @@ -76,19 +61,5 @@ def build(spinner: Spinner, dirty: bool = False, minimal: bool = False) -> None: t.wait_for_exit() exit(1) - # enforce max cache size - cache_files = [f for f in CACHE_DIR.rglob('*') if f.is_file()] - cache_files.sort(key=lambda f: f.stat().st_mtime) - cache_size = sum(f.stat().st_size for f in cache_files) - for f in cache_files: - if cache_size < MAX_CACHE_SIZE: - break - cache_size -= f.stat().st_size - f.unlink() - - if __name__ == "__main__": - spinner = Spinner() - spinner.update_progress(0, 100) - build_metadata = get_build_metadata() - build(spinner, build_metadata.openpilot.is_dirty, minimal = AGNOS) + build() diff --git a/system/manager/helpers.py b/system/manager/helpers.py index 047d0ac2d6..6af4a799e4 100644 --- a/system/manager/helpers.py +++ b/system/manager/helpers.py @@ -46,8 +46,8 @@ def unblock_stdout() -> None: def write_onroad_params(started, params): - params.put_bool("IsOnroad", started) - params.put_bool("IsOffroad", not started) + params.put_bool("IsOnroad", started, block=True) + params.put_bool("IsOffroad", not started, block=True) def save_bootlog(): diff --git a/system/manager/manager.py b/system/manager/manager.py index 15a09d0a37..0eb55c2727 100755 --- a/system/manager/manager.py +++ b/system/manager/manager.py @@ -40,7 +40,7 @@ def manager_init() -> None: # device boot mode if params.get("DeviceBootMode") == 1: # start in Always Offroad mode - params.put_bool("OffroadMode", True) + params.put_bool("OffroadMode", True, block=True) # quick boot if params.get_bool("QuickBootToggle") and not PC: @@ -49,7 +49,7 @@ def manager_init() -> None: open(prebuilt_path, 'x').close() if params.get_bool("RecordFrontLock"): - params.put_bool("RecordFront", True) + params.put_bool("RecordFront", True, block=True) if not PC: run_migration(params) @@ -58,7 +58,7 @@ def manager_init() -> None: for k in params.all_keys(): default_value = params.get_default_value(k) if default_value is not None and params.get(k) is None: - params.put(k, default_value) + params.put(k, default_value, block=True) # Create folders needed for msgq try: @@ -70,16 +70,16 @@ def manager_init() -> None: # set params serial = HARDWARE.get_serial() - params.put("Version", build_metadata.openpilot.version) - params.put("GitCommit", build_metadata.openpilot.git_commit) - params.put("GitCommitDate", build_metadata.openpilot.git_commit_date) - params.put("GitBranch", build_metadata.channel) - params.put("GitRemote", build_metadata.openpilot.git_origin) - params.put_bool("IsDevelopmentBranch", build_metadata.development_channel) - params.put_bool("IsTestedBranch", build_metadata.tested_channel) - params.put_bool("IsReleaseBranch", build_metadata.release_channel) - params.put_bool("IsReleaseSpBranch", build_metadata.release_sp_channel) - params.put("HardwareSerial", serial) + params.put("Version", build_metadata.openpilot.version, block=True) + params.put("GitCommit", build_metadata.openpilot.git_commit, block=True) + params.put("GitCommitDate", build_metadata.openpilot.git_commit_date, block=True) + params.put("GitBranch", build_metadata.channel, block=True) + params.put("GitRemote", build_metadata.openpilot.git_origin, block=True) + params.put_bool("IsDevelopmentBranch", build_metadata.development_channel, block=True) + params.put_bool("IsTestedBranch", build_metadata.tested_channel, block=True) + params.put_bool("IsReleaseBranch", build_metadata.release_channel, block=True) + params.put_bool("IsReleaseSpBranch", build_metadata.release_sp_channel, block=True) + params.put("HardwareSerial", serial, block=True) # set dongle id reg_res = register(show_spinner=True) @@ -191,7 +191,7 @@ def manager_thread() -> None: for param in ("DoUninstall", "DoShutdown", "DoReboot"): if params.get_bool(param): shutdown = True - params.put("LastManagerExitReason", f"{param} {datetime.datetime.now()}") + params.put("LastManagerExitReason", f"{param} {datetime.datetime.now()}", block=True) cloudlog.warning(f"Shutting down manager - {param} set") if shutdown: diff --git a/system/manager/process.py b/system/manager/process.py index 36e1ba77b2..cdb316e1a1 100644 --- a/system/manager/process.py +++ b/system/manager/process.py @@ -190,12 +190,8 @@ class PythonProcess(ManagerProcess): if self.proc is not None: return - # TODO: this is just a workaround for this tinygrad check: - # https://github.com/tinygrad/tinygrad/blob/ac9c96dae1656dc220ee4acc39cef4dd449aa850/tinygrad/device.py#L26 - name = self.name if "modeld" not in self.name else "MainProcess" - cloudlog.info(f"starting python {self.module}") - self.proc = Process(name=name, target=self.launcher, args=(self.module, self.name)) + self.proc = Process(name=self.name, target=self.launcher, args=(self.module, self.name)) self.proc.start() self.shutting_down = False @@ -240,7 +236,7 @@ class DaemonProcess(ManagerProcess): stderr=open('/dev/null', 'w'), preexec_fn=os.setpgrp) - self.params.put(self.param_name, proc.pid) + self.params.put(self.param_name, proc.pid, block=True) def stop(self, retry=True, block=True, sig=None) -> None: pass diff --git a/system/manager/process_config.py b/system/manager/process_config.py index a9ecf302f2..2b8def95b5 100644 --- a/system/manager/process_config.py +++ b/system/manager/process_config.py @@ -34,7 +34,7 @@ def ublox_available() -> bool: def ublox(started: bool, params: Params, CP: car.CarParams) -> bool: use_ublox = ublox_available() if use_ublox != params.get_bool("UbloxAvailable"): - params.put_bool("UbloxAvailable", use_ublox) + params.put_bool("UbloxAvailable", use_ublox, block=True) return started and use_ublox def joystick(started: bool, params: Params, CP: car.CarParams) -> bool: @@ -148,6 +148,7 @@ procs = [ PythonProcess("lateral_maneuversd", "tools.lateral_maneuvers.lateral_maneuversd", lat_maneuver), PythonProcess("radard", "selfdrive.controls.radard", only_onroad), PythonProcess("hardwared", "system.hardware.hardwared", always_run), + PythonProcess("modem", "system.hardware.tici.modem", always_run, enabled=TICI), PythonProcess("tombstoned", "system.tombstoned", always_run, enabled=not PC), PythonProcess("updated", "system.updated.updated", only_offroad, enabled=not PC), PythonProcess("uploader", "system.loggerd.uploader", uploader_ready), diff --git a/system/qcomgpsd/qcomgpsd.py b/system/qcomgpsd/qcomgpsd.py index 47d64ff4e9..7e0d304872 100755 --- a/system/qcomgpsd/qcomgpsd.py +++ b/system/qcomgpsd/qcomgpsd.py @@ -1,15 +1,13 @@ #!/usr/bin/env python3 +import fcntl import os import sys import signal import itertools import math import time -import requests -import shutil from serial import Serial import datetime -from multiprocessing import Process, Event from typing import NoReturn from struct import unpack_from, calcsize, pack @@ -30,9 +28,6 @@ from openpilot.system.qcomgpsd.structs import (dict_unpacker, position_report, r LOG_GNSS_OEMDRE_SVPOLY_REPORT) DEBUG = int(os.getenv("DEBUG", "0"))==1 -ASSIST_DATA_FILE = '/tmp/xtra3grc.bin' -ASSIST_DATA_FILE_DOWNLOAD = ASSIST_DATA_FILE + '.download' -ASSISTANCE_URL = 'http://xtrapath3.izatcloud.net/xtra3grc.bin' LOG_TYPES = [ LOG_GNSS_GPS_MEASUREMENT_REPORT, @@ -91,70 +86,32 @@ def try_setup_logs(diag, logs): return setup_logs(diag, logs) AT_PORT = "/dev/modem_at0" +AT_LOCK = "/dev/shm/modem.lock" # shared with modem.py and LPA @retry(attempts=5, delay=1.0) def at_cmd(cmd: str) -> str: - with Serial(AT_PORT, baudrate=115200, timeout=5) as ser: - ser.reset_input_buffer() - ser.write(f"{cmd}\r".encode()) - lines = [] - while True: - line = ser.readline() - if not line: - raise RuntimeError(f"AT command timeout: {cmd}") - line = line.decode('utf-8', errors='replace').strip() - if line in ("OK", "ERROR") or line.startswith("+CME ERROR"): - break - if line and line != cmd: - lines.append(line) - return '\n'.join(lines) + with os.fdopen(os.open(AT_LOCK, os.O_CREAT | os.O_RDWR, 0o666), "r+") as lock: + fcntl.flock(lock.fileno(), fcntl.LOCK_EX) + with Serial(AT_PORT, baudrate=115200, timeout=5) as ser: + ser.reset_input_buffer() + ser.write(f"{cmd}\r".encode()) + lines = [] + while True: + line = ser.readline() + if not line: + raise RuntimeError(f"AT command timeout: {cmd}") + line = line.decode('utf-8', errors='replace').strip() + if line in ("OK", "ERROR") or line.startswith("+CME ERROR"): + break + if line and line != cmd: + lines.append(line) + return '\n'.join(lines) def gps_enabled() -> bool: return "QGPS: 1" in at_cmd("AT+QGPS?") -def download_assistance(): - try: - response = requests.get(ASSISTANCE_URL, timeout=5, stream=True) - - with open(ASSIST_DATA_FILE_DOWNLOAD, 'wb') as fp: - for chunk in response.iter_content(chunk_size=8192): - fp.write(chunk) - if fp.tell() > 1e5: - cloudlog.error("Qcom assistance data larger than expected") - return - - os.rename(ASSIST_DATA_FILE_DOWNLOAD, ASSIST_DATA_FILE) - - except requests.exceptions.RequestException: - cloudlog.exception("Failed to download assistance file") - return - -def downloader_loop(event): - if os.path.exists(ASSIST_DATA_FILE): - os.remove(ASSIST_DATA_FILE) - - alt_path = os.getenv("QCOM_ALT_ASSISTANCE_PATH", None) - if alt_path is not None and os.path.exists(alt_path): - shutil.copyfile(alt_path, ASSIST_DATA_FILE) - - try: - while not os.path.exists(ASSIST_DATA_FILE) and not event.is_set(): - download_assistance() - event.wait(timeout=10) - except KeyboardInterrupt: - pass - -@retry(attempts=5, delay=0.2, ignore_failure=True) -def inject_assistance(): - import subprocess - cmd = f"mmcli -m any --timeout 30 --location-inject-assistance-data={ASSIST_DATA_FILE}" - subprocess.check_output(cmd, stderr=subprocess.PIPE, shell=True) - cloudlog.info("successfully loaded assistance data") - @retry(attempts=5, delay=1.0) -def setup_quectel(diag: ModemDiag) -> bool: - ret = False - +def setup_quectel(diag: ModemDiag): # enable OEMDRE in the NV # TODO: it has to reboot for this to take effect DIAG_NV_READ_F = 38 @@ -168,26 +125,11 @@ def setup_quectel(diag: ModemDiag) -> bool: if gps_enabled(): at_cmd("AT+QGPSEND") - if "GPS_COLD_START" in os.environ: - # deletes all assistance - at_cmd("AT+QGPSDEL=0") - else: - # allow module to perform hot start - at_cmd("AT+QGPSDEL=1") - # disable DPO power savings for more accuracy at_cmd("AT+QGPSCFG=\"dpoenable\",0") # don't automatically turn on GNSS on powerup at_cmd("AT+QGPSCFG=\"autogps\",0") - # Do internet assistance - at_cmd("AT+QGPSXTRA=1") - at_cmd("AT+QGPSSUPLURL=\"NULL\"") - if os.path.exists(ASSIST_DATA_FILE): - ret = True - inject_assistance() - os.remove(ASSIST_DATA_FILE) - #at_cmd("AT+QGPSXTRADATA?") if system_time_valid(): time_str = datetime.datetime.now(datetime.UTC).replace(tzinfo=None).strftime("%Y/%m/%d,%H:%M:%S") at_cmd(f"AT+QGPSXTRATIME=0,\"{time_str}\",1,1,1000") @@ -214,7 +156,6 @@ def setup_quectel(diag: ModemDiag) -> bool: 0,0 )) - return ret def teardown_quectel(diag): at_cmd("AT+QGPSCFG=\"outport\",\"none\"") @@ -255,9 +196,6 @@ def main() -> NoReturn: wait_for_modem() - stop_download_event = Event() - assist_fetch_proc = Process(target=downloader_loop, args=(stop_download_event,)) - assist_fetch_proc.start() def cleanup(sig, frame): cloudlog.warning("caught sig disabling quectel gps") @@ -268,18 +206,13 @@ def main() -> NoReturn: except NameError: cloudlog.warning('quectel not yet setup') - stop_download_event.set() - assist_fetch_proc.kill() - assist_fetch_proc.join() - sys.exit(0) signal.signal(signal.SIGINT, cleanup) signal.signal(signal.SIGTERM, cleanup) # connect to modem diag = ModemDiag() - r = setup_quectel(diag) - want_assistance = not r + setup_quectel(diag) cloudlog.warning("quectel setup done") gpio_init(GPIO.GNSS_PWR_EN, True) gpio_set(GPIO.GNSS_PWR_EN, True) @@ -287,10 +220,6 @@ def main() -> NoReturn: pm = messaging.PubMaster(['qcomGnss', 'gpsLocation']) while 1: - if os.path.exists(ASSIST_DATA_FILE) and want_assistance: - setup_quectel(diag) - want_assistance = False - opcode, payload = diag.recv() if opcode != DIAG_LOG_F: cloudlog.error(f"Unhandled opcode: {opcode}") @@ -383,9 +312,6 @@ def main() -> NoReturn: gps.speedAccuracy = math.sqrt(sum([x**2 for x in vNEDsigma])) # quectel gps verticalAccuracy is clipped to 500, set invalid if so gps.hasFix = gps.verticalAccuracy != 500 - if gps.hasFix: - want_assistance = False - stop_download_event.set() pm.send('gpsLocation', msg) elif log_type == LOG_GNSS_OEMDRE_SVPOLY_REPORT: diff --git a/system/qcomgpsd/tests/test_qcomgpsd.py b/system/qcomgpsd/tests/test_qcomgpsd.py deleted file mode 100644 index 75e8707591..0000000000 --- a/system/qcomgpsd/tests/test_qcomgpsd.py +++ /dev/null @@ -1,119 +0,0 @@ -import os -import pytest -import time -import datetime - -import cereal.messaging as messaging -from openpilot.system.qcomgpsd.qcomgpsd import at_cmd, wait_for_modem -from openpilot.system.manager.process_config import managed_processes - -GOOD_SIGNAL = bool(int(os.getenv("GOOD_SIGNAL", '0'))) - - -@pytest.mark.tici -class TestRawgpsd: - @classmethod - def setup_class(cls): - os.environ['GPS_COLD_START'] = '1' - os.system("sudo systemctl start systemd-resolved") - os.system("sudo systemctl restart ModemManager lte") - wait_for_modem() - - @classmethod - def teardown_class(cls): - managed_processes['qcomgpsd'].stop() - os.system("sudo systemctl restart systemd-resolved") - os.system("sudo systemctl restart ModemManager lte") - - def setup_method(self): - self.sm = messaging.SubMaster(['qcomGnss', 'gpsLocation', 'gnssMeasurements']) - - def teardown_method(self): - managed_processes['qcomgpsd'].stop() - os.system("sudo systemctl restart systemd-resolved") - - def _wait_for_output(self, t): - dt = 0.1 - for _ in range(t*int(1/dt)): - self.sm.update(0) - if self.sm.updated['qcomGnss']: - break - time.sleep(dt) - return self.sm.updated['qcomGnss'] - - def test_no_crash_double_command(self): - wait_for_modem() - at_cmd("AT+QGPSDEL=0") - at_cmd("AT+QGPSDEL=0") - - def test_wait_for_modem(self): - os.system("sudo systemctl stop ModemManager") - managed_processes['qcomgpsd'].start() - assert self._wait_for_output(30) - - def test_startup_time(self, subtests): - for internet in (True, False): - if not internet: - os.system("sudo systemctl stop systemd-resolved") - with subtests.test(internet=internet): - managed_processes['qcomgpsd'].start() - assert self._wait_for_output(30) - managed_processes['qcomgpsd'].stop() - - def test_turns_off_gnss(self, subtests): - for s in (0.1, 1, 5): - with subtests.test(runtime=s): - managed_processes['qcomgpsd'].start() - time.sleep(s) - managed_processes['qcomgpsd'].stop() - - wait_for_modem() - resp = at_cmd("AT+QGPS?") - assert "+QGPS: 0" in resp - - - def check_assistance(self, should_be_loaded): - # after QGPSDEL: '+QGPSXTRADATA: 0,"1980/01/05,19:00:00"' - # after loading: '+QGPSXTRADATA: 10080,"2023/06/24,19:00:00"' - wait_for_modem() - out = at_cmd("AT+QGPSXTRADATA?") - out = out.split("+QGPSXTRADATA:")[1].split("'")[0].strip() - valid_duration, injected_time_str = out.split(",", 1) - if should_be_loaded: - assert valid_duration == "10080" # should be max time - injected_time = datetime.datetime.strptime(injected_time_str.replace("\"", ""), "%Y/%m/%d,%H:%M:%S") - assert abs((datetime.datetime.now(datetime.UTC).replace(tzinfo=None) - injected_time).total_seconds()) < 60*60*12 - else: - valid_duration, injected_time_str = out.split(",", 1) - injected_time_str = injected_time_str.replace('\"', '').replace('\'', '') - assert injected_time_str[:] == '1980/01/05,19:00:00'[:] - assert valid_duration == '0' - - @pytest.mark.skip(reason="XTRA injection via QMI needs debugging on AGNOS 17") - def test_assistance_loading(self): - managed_processes['qcomgpsd'].start() - assert self._wait_for_output(30) - managed_processes['qcomgpsd'].stop() - self.check_assistance(True) - - @pytest.mark.skip(reason="XTRA injection via QMI needs debugging on AGNOS 17") - def test_no_assistance_loading(self): - os.system("sudo systemctl stop systemd-resolved") - - managed_processes['qcomgpsd'].start() - assert self._wait_for_output(30) - managed_processes['qcomgpsd'].stop() - self.check_assistance(False) - - @pytest.mark.skip(reason="XTRA injection via QMI needs debugging on AGNOS 17") - def test_late_assistance_loading(self): - os.system("sudo systemctl stop systemd-resolved") - - managed_processes['qcomgpsd'].start() - self._wait_for_output(17) - assert self.sm.updated['qcomGnss'] - - os.system("sudo systemctl restart systemd-resolved") - time.sleep(15) - managed_processes['qcomgpsd'].stop() - self.check_assistance(True) diff --git a/system/sensord/sensord.py b/system/sensord/sensord.py index 62908c6f18..ce6fb9ccb2 100755 --- a/system/sensord/sensord.py +++ b/system/sensord/sensord.py @@ -11,19 +11,21 @@ from openpilot.common.utils import sudo_write from openpilot.common.realtime import config_realtime_process, Ratekeeper from openpilot.common.swaglog import cloudlog from openpilot.common.gpio import gpiochip_get_ro_value_fd, gpioevent_data -from openpilot.system.hardware import HARDWARE from openpilot.system.sensord.sensors.i2c_sensor import Sensor from openpilot.system.sensord.sensors.lsm6ds3_accel import LSM6DS3_Accel from openpilot.system.sensord.sensors.lsm6ds3_gyro import LSM6DS3_Gyro from openpilot.system.sensord.sensors.lsm6ds3_temp import LSM6DS3_Temp -from openpilot.system.sensord.sensors.mmc5603nj_magn import MMC5603NJ_Magn I2C_BUS_IMU = 1 def interrupt_loop(sensors: list[tuple[Sensor, str, bool]], event) -> None: pm = messaging.PubMaster([service for sensor, service, interrupt in sensors if interrupt]) + # NOTE: the gyro and accelerometer share an IRQ due to the comma three + # routing only one GPIO from the LSM to the SOC, but comma 3X and four + # have two. if we want better timestamps in the future, we can use both. + # Requesting both edges as the data ready pulse from the lsm6ds sensor is # very short (75us) and is mostly detected as falling edge instead of rising. # So if it is detected as rising the following falling edge is skipped. @@ -97,10 +99,6 @@ def main() -> None: (LSM6DS3_Gyro(I2C_BUS_IMU), "gyroscope", True), (LSM6DS3_Temp(I2C_BUS_IMU), "temperatureSensor", False), ] - if HARDWARE.get_device_type() == "tizi": - sensors_cfg.append( - (MMC5603NJ_Magn(I2C_BUS_IMU), "magnetometer", False), - ) # Reset sensors for sensor, _, _ in sensors_cfg: diff --git a/system/sensord/sensors/lsm6ds3_accel.py b/system/sensord/sensors/lsm6ds3_accel.py index 43863daa93..761ae828bb 100644 --- a/system/sensord/sensors/lsm6ds3_accel.py +++ b/system/sensord/sensors/lsm6ds3_accel.py @@ -77,13 +77,9 @@ class LSM6DS3_Accel(Sensor): event = log.SensorEventData.new_message() event.timestamp = ts - event.version = 1 - event.sensor = 1 # SENSOR_ACCELEROMETER - event.type = 1 # SENSOR_TYPE_ACCELEROMETER event.source = self.source a = event.init('acceleration') a.v = [y, -x, z] - a.status = 1 return event def shutdown(self) -> None: diff --git a/system/sensord/sensors/lsm6ds3_gyro.py b/system/sensord/sensors/lsm6ds3_gyro.py index 60de2bbe02..654cff9da8 100644 --- a/system/sensord/sensors/lsm6ds3_gyro.py +++ b/system/sensord/sensors/lsm6ds3_gyro.py @@ -73,13 +73,9 @@ class LSM6DS3_Gyro(Sensor): event = log.SensorEventData.new_message() event.timestamp = ts - event.version = 2 - event.sensor = 5 # SENSOR_GYRO_UNCALIBRATED - event.type = 16 # SENSOR_TYPE_GYROSCOPE_UNCALIBRATED event.source = self.source g = event.init('gyroUncalibrated') g.v = xyz - g.status = 1 return event def shutdown(self) -> None: diff --git a/system/sensord/sensors/lsm6ds3_temp.py b/system/sensord/sensors/lsm6ds3_temp.py index b9bb9fe3da..ffe970c22c 100644 --- a/system/sensord/sensors/lsm6ds3_temp.py +++ b/system/sensord/sensors/lsm6ds3_temp.py @@ -23,7 +23,6 @@ class LSM6DS3_Temp(Sensor): def get_event(self, ts: int | None = None) -> log.SensorEventData: event = log.SensorEventData.new_message() - event.version = 1 event.timestamp = int(time.monotonic() * 1e9) event.source = self.source event.temperature = self._read_temperature() diff --git a/system/sensord/sensors/mmc5603nj_magn.py b/system/sensord/sensors/mmc5603nj_magn.py deleted file mode 100644 index 255e99eb3e..0000000000 --- a/system/sensord/sensors/mmc5603nj_magn.py +++ /dev/null @@ -1,76 +0,0 @@ -import time - -from cereal import log -from openpilot.system.sensord.sensors.i2c_sensor import Sensor - -# https://www.mouser.com/datasheet/2/821/Memsic_09102019_Datasheet_Rev.B-1635324.pdf - -# Register addresses -REG_ODR = 0x1A -REG_INTERNAL_0 = 0x1B -REG_INTERNAL_1 = 0x1C - -# Control register settings -CMM_FREQ_EN = (1 << 7) -AUTO_SR_EN = (1 << 5) -SET = (1 << 3) -RESET = (1 << 4) - -class MMC5603NJ_Magn(Sensor): - @property - def device_address(self) -> int: - return 0x30 - - def init(self): - self.verify_chip_id(0x39, [0x10, ]) - self.writes(( - (REG_ODR, 0), - - # Set BW to 0b01 for 1-150 Hz operation - (REG_INTERNAL_1, 0b01), - )) - - def _read_data(self, cycle) -> list[float]: - # start measurement - self.write(REG_INTERNAL_0, cycle) - self.wait() - - # read out XYZ - scale = 1.0 / 16384.0 - b = self.read(0x00, 9) - return [ - (self.parse_20bit(b[6], b[1], b[0]) * scale) - 32.0, - (self.parse_20bit(b[7], b[3], b[2]) * scale) - 32.0, - (self.parse_20bit(b[8], b[5], b[4]) * scale) - 32.0, - ] - - def get_event(self, ts: int | None = None) -> log.SensorEventData: - ts = time.monotonic_ns() - - # SET - RESET cycle - xyz = self._read_data(SET) - reset_xyz = self._read_data(RESET) - vals = [*xyz, *reset_xyz] - - event = log.SensorEventData.new_message() - event.timestamp = ts - event.version = 1 - event.sensor = 3 # SENSOR_MAGNETOMETER_UNCALIBRATED - event.type = 14 # SENSOR_TYPE_MAGNETIC_FIELD_UNCALIBRATED - event.source = log.SensorEventData.SensorSource.mmc5603nj - - m = event.init('magneticUncalibrated') - m.v = vals - m.status = int(all(int(v) != -32 for v in vals)) - - return event - - def shutdown(self) -> None: - v = self.read(REG_INTERNAL_0, 1)[0] - self.writes(( - # disable auto-reset of measurements - (REG_INTERNAL_0, (v & (~(CMM_FREQ_EN | AUTO_SR_EN)))), - - # disable continuous mode - (REG_ODR, 0), - )) diff --git a/system/sensord/tests/test_sensord.py b/system/sensord/tests/test_sensord.py index 20214e12ff..3d7d26f9fa 100644 --- a/system/sensord/tests/test_sensord.py +++ b/system/sensord/tests/test_sensord.py @@ -5,44 +5,19 @@ import numpy as np from collections import namedtuple, defaultdict import cereal.messaging as messaging -from cereal import log from cereal.services import SERVICE_LIST from openpilot.common.gpio import get_irqs_for_action from openpilot.common.timeout import Timeout -from openpilot.system.hardware import HARDWARE from openpilot.system.manager.process_config import managed_processes -LSM = { - ('lsm6ds3', 'acceleration'), - ('lsm6ds3', 'gyroUncalibrated'), - ('lsm6ds3', 'temperature'), -} -LSM_C = {(x[0]+'trc', x[1]) for x in LSM} +SensorConfig = namedtuple('SensorConfig', ['service', 'measurement', 'sanity_min', 'sanity_max', 'std_max']) -MMC = { - ('mmc5603nj', 'magneticUncalibrated'), -} - -SENSOR_CONFIGURATIONS: list[set] = { - "mici": [LSM, LSM_C], - "tizi": [MMC | LSM, MMC | LSM_C], - "tici": [LSM, LSM_C, MMC | LSM, MMC | LSM_C], -}.get(HARDWARE.get_device_type(), []) - -Sensor = log.SensorEventData.SensorSource -SensorConfig = namedtuple('SensorConfig', ['type', 'sanity_min', 'sanity_max']) -ALL_SENSORS = { - Sensor.lsm6ds3trc: { - SensorConfig("acceleration", 5, 15), - SensorConfig("gyroUncalibrated", 0, .2), - SensorConfig("temperature", 10, 40), # set for max range of our office - }, - - Sensor.mmc5603nj: { - SensorConfig("magneticUncalibrated", 0, 300), - } -} -ALL_SENSORS[Sensor.lsm6ds3] = ALL_SENSORS[Sensor.lsm6ds3trc] +SENSOR_CONFIGS = ( + SensorConfig("accelerometer", "acceleration", 5, 15, 5), + SensorConfig("gyroscope", "gyroUncalibrated", 0, .15, 0.5), + SensorConfig("temperatureSensor", "temperature", 10, 40, 0.5), # set for max range of our office +) +SENSOR_CONFIGS_BY_MEASUREMENT = {config.measurement: config for config in SENSOR_CONFIGS} def get_irq_count(irq: int): with open(f"/sys/kernel/irq/{irq}/per_cpu_count") as f: @@ -50,12 +25,11 @@ def get_irq_count(irq: int): return sum(per_cpu) def read_sensor_events(duration_sec): - sensor_types = ['accelerometer', 'gyroscope', 'magnetometer', 'temperatureSensor',] socks = {} poller = messaging.Poller() events = defaultdict(list) - for stype in sensor_types: - socks[stype] = messaging.sub_sock(stype, poller=poller, timeout=100) + for config in SENSOR_CONFIGS: + socks[config.service] = messaging.sub_sock(config.service, poller=poller, timeout=100) # wait for sensors to come up with Timeout(int(os.environ.get("SENSOR_WAIT", "5")), "sensors didn't come up"): @@ -70,11 +44,15 @@ def read_sensor_events(duration_sec): for s in socks: events[s] += messaging.drain_sock(socks[s]) time.sleep(0.1) - assert sum(map(len, events.values())) != 0, "No sensor events collected!" return {k: v for k, v in events.items() if len(v) > 0} +def iter_measurements(events): + for msgs in events.values(): + for measurement in msgs: + yield measurement, getattr(measurement, measurement.which()) + @pytest.mark.tici class TestSensord: @classmethod @@ -102,31 +80,19 @@ class TestSensord: def teardown_method(self): managed_processes["sensord"].stop() - def test_sensors_present(self): - # verify correct sensors configuration - seen = set() - for etype in self.events: - for measurement in self.events[etype]: - m = getattr(measurement, measurement.which()) - seen.add((str(m.source), m.which())) - - assert seen in SENSOR_CONFIGURATIONS + def test_all_sensors_present(self): + missing = [config.service for config in SENSOR_CONFIGS if config.service not in self.events] + assert len(missing) == 0, f"missing sensors: {missing}" def test_lsm6ds3_timing(self, subtests): # verify measurements are sampled and published at 104Hz - sensor_t = { - 1: [], # accel - 5: [], # gyro - } + sensor_t = {service: [] for service in ('accelerometer', 'gyroscope')} - for measurement in self.events['accelerometer']: - m = getattr(measurement, measurement.which()) - sensor_t[m.sensor].append(m.timestamp) - - for measurement in self.events['gyroscope']: - m = getattr(measurement, measurement.which()) - sensor_t[m.sensor].append(m.timestamp) + for service in sensor_t: + for measurement in self.events.get(service, []): + m = getattr(measurement, measurement.which()) + sensor_t[service].append(m.timestamp) for s, vals in sensor_t.items(): with subtests.test(sensor=s): @@ -153,19 +119,16 @@ class TestSensord: def test_logmonottime_timestamp_diff(self): # ensure diff between the message logMonotime and sample timestamp is small - tdiffs = list() - for etype in self.events: - for measurement in self.events[etype]: - m = getattr(measurement, measurement.which()) + tdiffs = [] + for measurement, m in iter_measurements(self.events): + # check if gyro and accel timestamps are before logMonoTime + if str(m.source).startswith("lsm6ds3") and m.which() != 'temperature': + err_msg = f"Timestamp after logMonoTime: {m.timestamp} > {measurement.logMonoTime}" + assert m.timestamp < measurement.logMonoTime, err_msg - # check if gyro and accel timestamps are before logMonoTime - if str(m.source).startswith("lsm6ds3") and m.which() != 'temperature': - err_msg = f"Timestamp after logMonoTime: {m.timestamp} > {measurement.logMonoTime}" - assert m.timestamp < measurement.logMonoTime, err_msg - - # negative values might occur, as non interrupt packages created - # before the sensor is read - tdiffs.append(abs(measurement.logMonoTime - m.timestamp) / 1e6) + # negative values might occur, as non interrupt packages created + # before the sensor is read + tdiffs.append(abs(measurement.logMonoTime - m.timestamp) / 1e6) # some sensors have a read procedure that will introduce an expected diff on the order of 20ms high_delay_diffs = set(filter(lambda d: d >= 25., tdiffs)) @@ -175,32 +138,29 @@ class TestSensord: assert avg_diff < 4, f"Avg packet diff: {avg_diff:.1f}ms" def test_sensor_values(self): - sensor_values = dict() - for etype in self.events: - for measurement in self.events[etype]: - m = getattr(measurement, measurement.which()) - key = (m.source.raw, m.which()) - values = getattr(m, m.which()) + sensor_values = defaultdict(list) + for _, m in iter_measurements(self.events): + key = (m.source.raw, m.which()) + values = getattr(m, m.which()) - if hasattr(values, 'v'): - values = values.v - values = np.atleast_1d(values) - - if key in sensor_values: - sensor_values[key].append(values) - else: - sensor_values[key] = [values] + if hasattr(values, 'v'): + values = values.v + sensor_values[key].append(np.atleast_1d(values)) # Sanity check sensor values - for sensor, stype in sensor_values: - for s in ALL_SENSORS[sensor]: - if s.type != stype: - continue + for (sensor, stype), values in sensor_values.items(): + config = SENSOR_CONFIGS_BY_MEASUREMENT[stype] - key = (sensor, s.type) - mean_norm = np.mean(np.linalg.norm(sensor_values[key], axis=1)) - err_msg = f"Sensor '{sensor} {s.type}' failed sanity checks {mean_norm} is not between {s.sanity_min} and {s.sanity_max}" - assert s.sanity_min <= mean_norm <= s.sanity_max, err_msg + if config.measurement == 'temperature': + measurement_stat = np.mean(values) + else: + measurement_stat = np.mean(np.linalg.norm(values, axis=1)) + err_msg = f"Sensor '{sensor} {config.measurement}' failed sanity checks {measurement_stat} is not between {config.sanity_min} and {config.sanity_max}" + assert config.sanity_min <= measurement_stat <= config.sanity_max, err_msg + + std_dev = np.std(values, axis=0) + err_msg = f"Sensor '{sensor} {config.measurement}' failed std dev test {std_dev} is not under {config.std_max}" + assert np.all(std_dev <= config.std_max), err_msg def test_sensor_verify_no_interrupts_after_stop(self): managed_processes["sensord"].start() @@ -222,4 +182,3 @@ class TestSensord: time.sleep(1) state_two = get_irq_count(self.sensord_irq) assert state_one == state_two, "Interrupts received after sensord stop!" - diff --git a/system/ui/lib/application.py b/system/ui/lib/application.py index a9e2982c95..42c0db7545 100644 --- a/system/ui/lib/application.py +++ b/system/ui/lib/application.py @@ -321,8 +321,9 @@ class GuiApplication(GuiApplicationExt): self._ffmpeg_thread = threading.Thread(target=self._ffmpeg_writer_thread, daemon=True) self._ffmpeg_thread.start() - # OFFSCREEN disables FPS limiting for fast offline rendering (e.g. clips) - rl.set_target_fps(0 if OFFSCREEN else fps) + # four display runs slightly faster than 60 FPS, let it dictate rate so we don't drift and drop frames + vblank_control = HARDWARE.get_device_type() == 'mici' + rl.set_target_fps(0 if OFFSCREEN or vblank_control else fps) self._target_fps = fps self._set_styles() @@ -590,6 +591,8 @@ class GuiApplication(GuiApplicationExt): self._render_profiler.enable() while not (self._window_close_requested or rl.window_should_close()): + frame_start = time.monotonic() + if PC: # Thread is not used on PC, need to manually add mouse events self._mouse._handle_mouse_event() @@ -604,7 +607,7 @@ class GuiApplication(GuiApplicationExt): if PC: rl.poll_input_events() time.sleep(1 / self._target_fps) - yield False + yield False, 0.0, 0.0 continue if self._render_texture: @@ -626,7 +629,9 @@ class GuiApplication(GuiApplicationExt): for widget in self._nav_stack[-self._nav_stack_widgets_to_render:]: widget.render(rl.Rectangle(0, 0, self.width, self.height)) - yield True + frame_time = rl.get_frame_time() + cpu_time = time.monotonic() - frame_start + yield True, frame_time, cpu_time if self._scale != 1.0: rl.rl_pop_matrix() diff --git a/system/ui/lib/multilang.py b/system/ui/lib/multilang.py index 9d25427867..c7d39e4794 100644 --- a/system/ui/lib/multilang.py +++ b/system/ui/lib/multilang.py @@ -177,7 +177,7 @@ class Multilang: self._plurals = {} def change_language(self, language_code: str) -> None: - self._params.put("LanguageSetting", language_code) + self._params.put("LanguageSetting", language_code, block=True) self._language = language_code self.setup() diff --git a/system/ui/lib/scroll_panel2.py b/system/ui/lib/scroll_panel2.py index 18fd8a9a67..7fae60119c 100644 --- a/system/ui/lib/scroll_panel2.py +++ b/system/ui/lib/scroll_panel2.py @@ -14,6 +14,7 @@ MIN_DRAG_PIXELS = 12 AUTO_SCROLL_TC_SNAP = 0.025 AUTO_SCROLL_TC = 0.18 BOUNCE_RETURN_RATE = 10.0 +SNAP_RATE = 6.3 # matches previous Scroller snapping. exp rate of approach to snap target, 1/s REJECT_DECELERATION_FACTOR = 3 MAX_SPEED = 10000.0 # px/s @@ -44,10 +45,8 @@ class ScrollState(Enum): class GuiScrollPanel2: - def __init__(self, horizontal: bool = True, handle_out_of_bounds: bool = True) -> None: + def __init__(self, horizontal: bool = True) -> None: self._horizontal = horizontal - self._handle_out_of_bounds = handle_out_of_bounds - self._AUTO_SCROLL_TC = AUTO_SCROLL_TC_SNAP if not self._handle_out_of_bounds else AUTO_SCROLL_TC self._state = ScrollState.STEADY self._offset: rl.Vector2 = rl.Vector2(0, 0) self._initial_click_event: MouseEvent | None = None @@ -63,7 +62,7 @@ class GuiScrollPanel2: def enabled(self) -> bool: return self._enabled() if callable(self._enabled) else self._enabled - def update(self, bounds: rl.Rectangle, content_size: float) -> float: + def update(self, bounds: rl.Rectangle, content_size: float, snap_target: float | None = None) -> float: if DEBUG: print('Old state:', self._state) @@ -73,7 +72,7 @@ class GuiScrollPanel2: self._handle_mouse_event(mouse_event, bounds, bounds_size, content_size) self._previous_mouse_event = mouse_event - self._update_state(bounds_size, content_size) + self._update_state(bounds_size, content_size, snap_target) if DEBUG: print('Velocity:', self._velocity) @@ -86,7 +85,7 @@ class GuiScrollPanel2: """Returns (max_offset, min_offset) for the given bounds and content size.""" return 0.0, min(0.0, bounds_size - content_size) - def _update_state(self, bounds_size: float, content_size: float) -> None: + def _update_state(self, bounds_size: float, content_size: float, snap_target: float | None) -> None: """Runs per render frame, independent of mouse events. Updates auto-scrolling state and velocity.""" max_offset, min_offset = self._get_offset_bounds(bounds_size, content_size) @@ -97,8 +96,9 @@ class GuiScrollPanel2: elif self._state == ScrollState.AUTO_SCROLL: # simple exponential return if out of bounds + # out of bounds is handled by snapping, so skip if set out_of_bounds = self.get_offset() > max_offset or self.get_offset() < min_offset - if out_of_bounds and self._handle_out_of_bounds: + if out_of_bounds and snap_target is None: target = max_offset if self.get_offset() > max_offset else min_offset dt = rl.get_frame_time() or 1e-6 @@ -121,9 +121,23 @@ class GuiScrollPanel2: # Update the offset based on the current velocity dt = rl.get_frame_time() self.set_offset(self.get_offset() + self._velocity * dt) # Adjust the offset based on velocity - alpha = 1 - (dt / (self._AUTO_SCROLL_TC + dt)) + # fast decay in snap mode so velocity yields to the snap pull instead of fighting it + auto_scroll_tc = AUTO_SCROLL_TC_SNAP if snap_target is not None else AUTO_SCROLL_TC + alpha = 1 - (dt / (auto_scroll_tc + dt)) self._velocity *= alpha + # Ease toward snap target when not in user control. Composes with velocity coast above: + # high velocity dominates initially, snap dominates as velocity decays. + if snap_target is not None and self._state not in (ScrollState.PRESSED, ScrollState.MANUAL_SCROLL): + snap_target = max(min_offset, min(max_offset, snap_target)) + dist = snap_target - self.get_offset() + if abs(dist) < 1: # finished snap + self.set_offset(snap_target) + else: + dt = rl.get_frame_time() or 1e-6 + factor = 1.0 - math.exp(-SNAP_RATE * dt) + self.set_offset(self.get_offset() + dist * factor) + def _handle_mouse_event(self, mouse_event: MouseEvent, bounds: rl.Rectangle, bounds_size: float, content_size: float) -> None: max_offset, min_offset = self._get_offset_bounds(bounds_size, content_size) diff --git a/system/ui/lib/wifi_manager.py b/system/ui/lib/wifi_manager.py index b83f7bacc9..87f0ebda83 100644 --- a/system/ui/lib/wifi_manager.py +++ b/system/ui/lib/wifi_manager.py @@ -23,7 +23,7 @@ from openpilot.system.ui.lib.networkmanager import (NM, NM_WIRELESS_IFACE, NM_80 NM_802_11_AP_FLAGS_PRIVACY, NM_802_11_AP_FLAGS_WPS, NM_PATH, NM_IFACE, NM_ACCESS_POINT_IFACE, NM_SETTINGS_PATH, NM_SETTINGS_IFACE, NM_CONNECTION_IFACE, NM_DEVICE_IFACE, - NM_DEVICE_TYPE_WIFI, NM_DEVICE_TYPE_MODEM, NM_ACTIVE_CONNECTION_IFACE, + NM_DEVICE_TYPE_WIFI, NM_ACTIVE_CONNECTION_IFACE, NM_IP4_CONFIG_IFACE, NM_PROPERTIES_IFACE, NMDeviceState, NMDeviceStateReason) try: @@ -207,15 +207,16 @@ class WifiManager: def worker(): self._wait_for_wifi_device() + # TODO: wait for state thread to start before adding tethering connection, tiny race currently + self._scan_thread.start() + self._state_thread.start() + self._init_connections() if Params is not None and self._tethering_ssid not in self._connections: self._add_tethering_connection() self._init_wifi_state() - self._scan_thread.start() - self._state_thread.start() - self._tethering_password = self._get_tethering_password() cloudlog.debug("WifiManager initialized") @@ -930,89 +931,6 @@ class WifiManager: def __del__(self): self.stop() - def update_gsm_settings(self, roaming: bool, apn: str, metered: bool): - """Update GSM settings for cellular connection""" - - def worker(): - try: - lte_connection_path = self._get_lte_connection_path() - if not lte_connection_path: - cloudlog.warning("No LTE connection found") - return - - settings = self._get_connection_settings(lte_connection_path) - - if len(settings) == 0: - cloudlog.warning(f"Failed to get connection settings for {lte_connection_path}") - return - - # Ensure dicts exist - if 'gsm' not in settings: - settings['gsm'] = {} - if 'connection' not in settings: - settings['connection'] = {} - - changes = False - auto_config = apn == "" - - if settings['gsm'].get('auto-config', ('b', False))[1] != auto_config: - cloudlog.warning(f'Changing gsm.auto-config to {auto_config}') - settings['gsm']['auto-config'] = ('b', auto_config) - changes = True - - if settings['gsm'].get('apn', ('s', ''))[1] != apn: - cloudlog.warning(f'Changing gsm.apn to {apn}') - settings['gsm']['apn'] = ('s', apn) - changes = True - - if settings['gsm'].get('home-only', ('b', False))[1] == roaming: - cloudlog.warning(f'Changing gsm.home-only to {not roaming}') - settings['gsm']['home-only'] = ('b', not roaming) - changes = True - - # Unknown means NetworkManager decides - metered_int = int(MeteredType.UNKNOWN if metered else MeteredType.NO) - if settings['connection'].get('metered', ('i', 0))[1] != metered_int: - cloudlog.warning(f'Changing connection.metered to {metered_int}') - settings['connection']['metered'] = ('i', metered_int) - changes = True - - if changes: - # Update the connection settings (temporary update) - conn_addr = DBusAddress(lte_connection_path, bus_name=NM, interface=NM_CONNECTION_IFACE) - reply = self._router_main.send_and_get_reply(new_method_call(conn_addr, 'UpdateUnsaved', 'a{sa{sv}}', (settings,))) - - if reply.header.message_type == MessageType.error: - cloudlog.warning(f"Failed to update GSM settings: {reply}") - return - - self._activate_modem_connection(lte_connection_path) - except Exception as e: - cloudlog.exception(f"Error updating GSM settings: {e}") - - threading.Thread(target=worker, daemon=True).start() - - def _get_lte_connection_path(self) -> str | None: - try: - settings_addr = DBusAddress(NM_SETTINGS_PATH, bus_name=NM, interface=NM_SETTINGS_IFACE) - known_connections = self._router_main.send_and_get_reply(new_method_call(settings_addr, 'ListConnections')).body[0] - - for conn_path in known_connections: - settings = self._get_connection_settings(conn_path) - if settings and settings.get('connection', {}).get('id', ('s', ''))[1] == 'lte': - return str(conn_path) - except Exception as e: - cloudlog.exception(f"Error finding LTE connection: {e}") - return None - - def _activate_modem_connection(self, connection_path: str): - try: - modem_device = self._get_adapter(NM_DEVICE_TYPE_MODEM) - if modem_device and connection_path: - self._router_main.send_and_get_reply(new_method_call(self._nm, 'ActivateConnection', 'ooo', (connection_path, modem_device, "/"))) - except Exception as e: - cloudlog.exception(f"Error activating modem connection: {e}") - def stop(self): if not self._exit: self._exit = True diff --git a/system/ui/mici_setup.py b/system/ui/mici_setup.py index d04f08ca37..8f4541e9e6 100755 --- a/system/ui/mici_setup.py +++ b/system/ui/mici_setup.py @@ -316,7 +316,7 @@ class NetworkSetupPageBase(Scroller): def on_waiting_click(): offset = (self._wifi_button.rect.x + self._wifi_button.rect.width / 2) - (self._rect.x + self._rect.width / 2) - self._scroller.scroll_to(offset, smooth=True, block_interaction=True) + self._scroller.scroll_to(offset, smooth=True, block_interrupt=True, block_widget_interaction=True) # trigger grow when wifi button in view self._pending_wifi_grow_animation = True @@ -399,7 +399,7 @@ class NetworkSetupPageBase(Scroller): self._scroller._layout() end_offset = -(self._scroller.content_size - self._rect.width) remaining = self._scroller.scroll_panel.get_offset() - end_offset - self._scroller.scroll_to(remaining, smooth=True, block_interaction=True) + self._scroller.scroll_to(remaining, smooth=True, block_interrupt=True, block_widget_interaction=True) self._pending_continue_grow_animation = True def set_custom_software(self, custom_software: bool): diff --git a/system/ui/widgets/mici_keyboard.py b/system/ui/widgets/mici_keyboard.py index 75a3c29e6b..bc3041aa3c 100644 --- a/system/ui/widgets/mici_keyboard.py +++ b/system/ui/widgets/mici_keyboard.py @@ -353,7 +353,7 @@ class MiciKeyboard(Widget): # draw black circle behind selected key circle_alpha = int(self._selected_key_filter.x * 225) - rl.draw_circle_gradient(int(key_x + key.rect.width / 2), int(key_y + key.rect.height / 2), + rl.draw_circle_gradient(rl.Vector2(key_x + key.rect.width / 2, key_y + key.rect.height / 2), SELECTED_CHAR_FONT_SIZE, rl.Color(0, 0, 0, circle_alpha), rl.BLANK) else: # move other keys away from selected key a bit diff --git a/system/ui/widgets/network.py b/system/ui/widgets/network.py index 69be42f502..c2fc427c42 100644 --- a/system/ui/widgets/network.py +++ b/system/ui/widgets/network.py @@ -160,10 +160,6 @@ class AdvancedNetworkSettings(Widget): self._scroller = Scroller(items, line_separator=True, spacing=0) - # Set initial config - metered = self._params.get_bool("GsmMetered") - self._wifi_manager.update_gsm_settings(roaming_enabled, self._params.get("GsmApn") or "", metered) - def _on_network_updated(self, networks: list[Network]): self._tethering_action.set_enabled(True) self._tethering_action.set_state(self._wifi_manager.is_tethering_active()) @@ -185,9 +181,7 @@ class AdvancedNetworkSettings(Widget): self._wifi_manager.set_tethering_active(checked) def _toggle_roaming(self): - roaming_state = self._roaming_action.get_state() - self._params.put_bool("GsmRoaming", roaming_state) - self._wifi_manager.update_gsm_settings(roaming_state, self._params.get("GsmApn") or "", self._params.get_bool("GsmMetered")) + self._params.put_bool("GsmRoaming", self._roaming_action.get_state(), block=True) def _edit_apn(self): def update_apn(result: DialogResult): @@ -198,9 +192,7 @@ class AdvancedNetworkSettings(Widget): if apn == "": self._params.remove("GsmApn") else: - self._params.put("GsmApn", apn) - - self._wifi_manager.update_gsm_settings(self._params.get_bool("GsmRoaming"), apn, self._params.get_bool("GsmMetered")) + self._params.put("GsmApn", apn, block=True) current_apn = self._params.get("GsmApn") or "" self._keyboard.reset(min_text_size=0) @@ -210,9 +202,7 @@ class AdvancedNetworkSettings(Widget): gui_app.push_widget(self._keyboard) def _toggle_cellular_metered(self): - metered = self._cellular_metered_action.get_state() - self._params.put_bool("GsmMetered", metered) - self._wifi_manager.update_gsm_settings(self._params.get_bool("GsmRoaming"), self._params.get("GsmApn") or "", metered) + self._params.put_bool("GsmMetered", self._cellular_metered_action.get_state(), block=True) def _toggle_wifi_metered(self, metered): metered_type = {0: MeteredType.UNKNOWN, 1: MeteredType.YES, 2: MeteredType.NO}.get(metered, MeteredType.UNKNOWN) diff --git a/system/ui/widgets/scroller.py b/system/ui/widgets/scroller.py index a3a0d2b38f..b7b6bf5932 100644 --- a/system/ui/widgets/scroller.py +++ b/system/ui/widgets/scroller.py @@ -75,12 +75,13 @@ class _Scroller(Widget): self._items: list[Widget] = [] self._horizontal = horizontal self._snap_items = snap_items + assert not self._snap_items or self._horizontal, "Snapping is only supported for horizontal scrolling" self._spacing = spacing self._pad = pad self._reset_scroll_at_show = True - self._scrolling_to: tuple[float | None, bool] = (None, False) # target offset, block_interaction + self._scrolling_to: tuple[float | None, bool, bool] = (None, False, False) # target offset, block_interrupt, block_widget_interaction self._scrolling_to_filter = FirstOrderFilter(0.0, SCROLL_RC, 1 / gui_app.target_fps) self._zoom_filter = FirstOrderFilter(1.0, 0.2, 1 / gui_app.target_fps) self._zoom_out_t: float = 0.0 @@ -92,10 +93,7 @@ class _Scroller(Widget): self._item_pos_filter = BounceFilter(0.0, 0.05, 1 / gui_app.target_fps) - # when not pressed, snap to closest item to be center - self._scroll_snap_filter = FirstOrderFilter(0.0, 0.05, 1 / gui_app.target_fps) - - self.scroll_panel = GuiScrollPanel2(self._horizontal, handle_out_of_bounds=not self._snap_items) + self.scroll_panel = GuiScrollPanel2(self._horizontal) self._scroll_enabled: bool | Callable[[], bool] = True self._show_scroll_indicator = scroll_indicator and self._horizontal @@ -116,8 +114,8 @@ class _Scroller(Widget): def set_reset_scroll_at_show(self, scroll: bool): self._reset_scroll_at_show = scroll - def scroll_to(self, pos: float, smooth: bool = False, block_interaction: bool = False): - assert not block_interaction or smooth, "Instant scroll cannot block user interaction" + def scroll_to(self, pos: float, smooth: bool = False, block_interrupt: bool = False, block_widget_interaction: bool = False): + assert smooth or (not block_interrupt and not block_widget_interaction), "Instant scroll cannot block interaction" # already there if abs(pos) < 1: @@ -127,7 +125,7 @@ class _Scroller(Widget): scroll_offset = self.scroll_panel.get_offset() - pos if smooth: self._scrolling_to_filter.x = self.scroll_panel.get_offset() - self._scrolling_to = scroll_offset, block_interaction + self._scrolling_to = scroll_offset, block_interrupt, block_widget_interaction else: self.scroll_panel.set_offset(scroll_offset) @@ -148,7 +146,7 @@ class _Scroller(Widget): # preserve original touch valid callback original_touch_valid_callback = item._touch_valid_callback - item.set_touch_valid_callback(lambda: self.scroll_panel.is_touch_valid() and self.enabled and self._scrolling_to[0] is None + item.set_touch_valid_callback(lambda: self.scroll_panel.is_touch_valid() and self.enabled and not self._scrolling_to[2] and not self.moving_items and (original_touch_valid_callback() if original_touch_valid_callback else True)) @@ -175,56 +173,29 @@ class _Scroller(Widget): # Cancel auto-scroll if user starts manually scrolling (unless block_interaction) if (self.scroll_panel.state in (ScrollState.PRESSED, ScrollState.MANUAL_SCROLL) and self._scrolling_to[0] is not None and not self._scrolling_to[1]): - self._scrolling_to = None, False + self._scrolling_to = None, False, False if self._scrolling_to[0] is not None and len(self._pending_lift) == 0: self._scrolling_to_filter.update(self._scrolling_to[0]) self.scroll_panel.set_offset(self._scrolling_to_filter.x) - if abs(self._scrolling_to_filter.x - self._scrolling_to[0]) < 1: + if abs(self._scrolling_to_filter.x - self._scrolling_to[0]) < 1: # finished scroll self.scroll_panel.set_offset(self._scrolling_to[0]) - self._scrolling_to = None, False + self._scrolling_to = None, False, False def _get_scroll(self, visible_items: list[Widget], content_size: float) -> float: scroll_enabled = self._scroll_enabled() if callable(self._scroll_enabled) else self._scroll_enabled self.scroll_panel.set_enabled(scroll_enabled and self.enabled and not self._scrolling_to[1]) - self.scroll_panel.update(self._rect, content_size) - if not self._snap_items: - return self.scroll_panel.get_offset() - # Snap closest item to center - center_pos = self._rect.x + self._rect.width / 2 if self._horizontal else self._rect.y + self._rect.height / 2 - closest_delta_pos = float('inf') - scroll_snap_idx: int | None = None - for idx, item in enumerate(visible_items): - if self._horizontal: - delta_pos = (item.rect.x + item.rect.width / 2) - center_pos - else: - delta_pos = (item.rect.y + item.rect.height / 2) - center_pos - if abs(delta_pos) < abs(closest_delta_pos): - closest_delta_pos = delta_pos - scroll_snap_idx = idx + # Snap closest item to center. Skipped while scroll_to() is animating + snap_target: float | None = None + if self._snap_items and visible_items and self._scrolling_to[0] is None: + # TODO: this doesn't handle two small buttons at the edges well + center_pos = self._rect.x + self._rect.width / 2 + closest_delta_pos = min((((item.rect.x + item.rect.width / 2) - center_pos) for item in visible_items), key=abs) + snap_target = self.scroll_panel.get_offset() - closest_delta_pos - if scroll_snap_idx is not None: - snap_item = visible_items[scroll_snap_idx] - if self.is_pressed: - # no snapping until released - self._scroll_snap_filter.x = 0 - else: - # TODO: this doesn't handle two small buttons at the edges well - if self._horizontal: - snap_delta_pos = (center_pos - (snap_item.rect.x + snap_item.rect.width / 2)) / 10 - snap_delta_pos = min(snap_delta_pos, -self.scroll_panel.get_offset() / 10) - snap_delta_pos = max(snap_delta_pos, (self._rect.width - self.scroll_panel.get_offset() - content_size) / 10) - else: - snap_delta_pos = (center_pos - (snap_item.rect.y + snap_item.rect.height / 2)) / 10 - snap_delta_pos = min(snap_delta_pos, -self.scroll_panel.get_offset() / 10) - snap_delta_pos = max(snap_delta_pos, (self._rect.height - self.scroll_panel.get_offset() - content_size) / 10) - self._scroll_snap_filter.update(snap_delta_pos) - - self.scroll_panel.set_offset(self.scroll_panel.get_offset() + self._scroll_snap_filter.x) - - return self.scroll_panel.get_offset() + return self.scroll_panel.update(self._rect, content_size, snap_target=snap_target) @property def moving_items(self) -> bool: @@ -409,7 +380,7 @@ class _Scroller(Widget): self._move_lift.clear() self._pending_lift.clear() self._pending_move.clear() - self._scrolling_to = None, False + self._scrolling_to = None, False, False self._scrolling_to_filter.x = 0.0 def hide_event(self): diff --git a/system/updated/tests/test_base.py b/system/updated/tests/test_base.py index c4894f2711..db38bfa840 100644 --- a/system/updated/tests/test_base.py +++ b/system/updated/tests/test_base.py @@ -86,7 +86,7 @@ class TestBaseUpdate: mocker.patch("openpilot.common.basedir.BASEDIR", self.basedir) def set_target_branch(self, branch): - self.params.put("UpdaterTargetBranch", branch) + self.params.put("UpdaterTargetBranch", branch, block=True) def setup_basedir_release(self, release): self.params = Params() diff --git a/system/updated/tests/test_updated.py b/system/updated/tests/test_updated.py index d36d4dd4e1..18ee0e706a 100644 --- a/system/updated/tests/test_updated.py +++ b/system/updated/tests/test_updated.py @@ -28,7 +28,7 @@ def test_target_branch_migration_from_current_branch(mocker, device_type, branch ]) def test_target_branch_migration_from_param(mocker, device_type, branch, expected): params = Params() - params.put("UpdaterTargetBranch", branch) + params.put("UpdaterTargetBranch", branch, block=True) mocker.patch("openpilot.system.updated.updated.HARDWARE.get_device_type", return_value=device_type) diff --git a/system/updated/updated.py b/system/updated/updated.py index c10a7097ce..8e28f7c52d 100755 --- a/system/updated/updated.py +++ b/system/updated/updated.py @@ -65,7 +65,7 @@ class WaitTimeHelper: def write_time_to_param(params, param) -> None: t = datetime.datetime.now(datetime.UTC).replace(tzinfo=None) - params.put(param, t) + params.put(param, t, block=True) def run(cmd: list[str], cwd: str | None = None) -> str: return subprocess.check_output(cmd, cwd=cwd, stderr=subprocess.STDOUT, encoding='utf8') @@ -138,7 +138,7 @@ def init_overlay() -> None: cloudlog.info("preparing new safe staging area") params = Params() - params.put_bool("UpdateAvailable", False) + params.put_bool("UpdateAvailable", False, block=True) set_consistent_flag(False) dismount_overlay() run(["sudo", "rm", "-rf", STAGING_ROOT]) @@ -169,7 +169,7 @@ def init_overlay() -> None: run(["sudo", "chmod", "755", os.path.join(OVERLAY_METADATA, "work")]) git_diff = run(["git", "diff", "--submodule=diff"], OVERLAY_MERGED) - params.put("GitDiff", git_diff) + params.put("GitDiff", git_diff, block=True) cloudlog.info(f"git diff output:\n{git_diff}") @@ -260,19 +260,19 @@ class Updater: return run(["git", "rev-parse", "HEAD"], path).rstrip() def set_params(self, update_success: bool, failed_count: int, exception: str | None) -> None: - self.params.put("UpdateFailedCount", failed_count) - self.params.put("UpdaterTargetBranch", self.target_branch) + self.params.put("UpdateFailedCount", failed_count, block=True) + self.params.put("UpdaterTargetBranch", self.target_branch, block=True) - self.params.put_bool("UpdaterFetchAvailable", self.update_available) + self.params.put_bool("UpdaterFetchAvailable", self.update_available, block=True) if len(self.branches): - self.params.put("UpdaterAvailableBranches", ','.join(self.branches.keys())) + self.params.put("UpdaterAvailableBranches", ','.join(self.branches.keys()), block=True) last_uptime_onroad = self.params.get("UptimeOnroad", return_default=True) last_route_count = self.params.get("RouteCount", return_default=True) if update_success: - self.params.put("LastUpdateTime", datetime.datetime.now(datetime.UTC).replace(tzinfo=None)) - self.params.put("LastUpdateUptimeOnroad", last_uptime_onroad) - self.params.put("LastUpdateRouteCount", last_route_count) + self.params.put("LastUpdateTime", datetime.datetime.now(datetime.UTC).replace(tzinfo=None), block=True) + self.params.put("LastUpdateUptimeOnroad", last_uptime_onroad, block=True) + self.params.put("LastUpdateRouteCount", last_route_count, block=True) else: last_uptime_onroad = self.params.get("LastUpdateUptimeOnroad", return_default=True) last_route_count = self.params.get("LastUpdateRouteCount", return_default=True) @@ -280,7 +280,7 @@ class Updater: if exception is None: self.params.remove("LastUpdateException") else: - self.params.put("LastUpdateException", exception) + self.params.put("LastUpdateException", exception, block=True) # Write out current and new version info def get_description(basedir: str) -> str: @@ -303,11 +303,11 @@ class Updater: except Exception: cloudlog.exception("updater.get_description") return f"{version} / {branch} / {commit} / {commit_date}" - self.params.put("UpdaterCurrentDescription", get_description(BASEDIR)) - self.params.put("UpdaterCurrentReleaseNotes", parse_release_notes(BASEDIR)) - self.params.put("UpdaterNewDescription", get_description(FINALIZED)) - self.params.put("UpdaterNewReleaseNotes", parse_release_notes(FINALIZED)) - self.params.put_bool("UpdateAvailable", self.update_ready) + self.params.put("UpdaterCurrentDescription", get_description(BASEDIR), block=True) + self.params.put("UpdaterCurrentReleaseNotes", parse_release_notes(BASEDIR), block=True) + self.params.put("UpdaterNewDescription", get_description(FINALIZED), block=True) + self.params.put("UpdaterNewReleaseNotes", parse_release_notes(FINALIZED), block=True) + self.params.put_bool("UpdateAvailable", self.update_ready, block=True) # Handle user prompt for alert in ("Offroad_UpdateFailed", "Offroad_ConnectivityNeeded", "Offroad_ConnectivityNeededPrompt"): @@ -362,11 +362,11 @@ class Updater: def fetch_update(self) -> None: cloudlog.info("attempting git fetch inside staging overlay") - self.params.put("UpdaterState", "downloading...") + self.params.put("UpdaterState", "downloading...", block=True) # TODO: cleanly interrupt this and invalidate old update set_consistent_flag(False) - self.params.put_bool("UpdateAvailable", False) + self.params.put_bool("UpdateAvailable", False, block=True) setup_git_options(OVERLAY_MERGED) @@ -394,7 +394,7 @@ class Updater: handle_agnos_update() # Create the finalized, ready-to-swap update - self.params.put("UpdaterState", "finalizing update...") + self.params.put("UpdaterState", "finalizing update...", block=True) finalize_update() cloudlog.info("finalize success!") @@ -423,7 +423,7 @@ def main() -> None: if not params.get("InstallDate"): t = datetime.datetime.now(datetime.UTC).replace(tzinfo=None) - params.put("InstallDate", t) + params.put("InstallDate", t, block=True) updater = Updater() update_failed_count = 0 # TODO: Load from param? @@ -433,7 +433,7 @@ def main() -> None: set_consistent_flag(False) # set initial state - params.put("UpdaterState", "idle") + params.put("UpdaterState", "idle", block=True) # Run the update loop first_run = True @@ -457,7 +457,7 @@ def main() -> None: update_failed_count += 1 # check for update - params.put("UpdaterState", "checking...") + params.put("UpdaterState", "checking...", block=True) updater.check_for_update() # download update @@ -487,7 +487,7 @@ def main() -> None: OVERLAY_INIT.unlink(missing_ok=True) try: - params.put("UpdaterState", "idle") + params.put("UpdaterState", "idle", block=True) update_successful = (update_failed_count == 0) updater.set_params(update_successful, update_failed_count, exception) except Exception: diff --git a/system/webrtc/device/video.py b/system/webrtc/device/video.py index 50feab4f4a..8a07c5b9be 100644 --- a/system/webrtc/device/video.py +++ b/system/webrtc/device/video.py @@ -1,4 +1,5 @@ import asyncio +import struct import time import av @@ -7,6 +8,13 @@ from teleoprtc.tracks import TiciVideoStreamTrack from cereal import messaging from openpilot.common.realtime import DT_MDL, DT_DMON +# arbitrary 16-byte UUID identifying openpilot frame-timing SEI messages +TIMING_SEI_UUID = bytes([ + 0xa5, 0xe0, 0xc4, 0xa4, 0x5b, 0x6e, 0x4e, 0x1e, + 0x9c, 0x7e, 0x12, 0x34, 0x56, 0x78, 0x9a, 0xbc, +]) +_SEI_PREFIX = b'\x00\x00\x00\x01\x06\x05\x30' + TIMING_SEI_UUID + class LiveStreamVideoStreamTrack(TiciVideoStreamTrack): camera_to_sock_mapping = { @@ -19,9 +27,30 @@ class LiveStreamVideoStreamTrack(TiciVideoStreamTrack): dt = DT_DMON if camera_type == "driver" else DT_MDL super().__init__(camera_type, dt) - self._sock = messaging.sub_sock(self.camera_to_sock_mapping[camera_type], conflate=True) + self._sock = self._make_sock(camera_type) self._pts = 0 self._t0_ns = time.monotonic_ns() + self.timing_sei_enabled = False + + def _make_sock(self, camera_type: str) -> messaging.SubSocket: + return messaging.sub_sock(self.camera_to_sock_mapping[camera_type], conflate=True) + + def switch_camera(self, camera_type: str) -> None: + self._sock = self._make_sock(camera_type) + + def _build_frame_data(self, msg) -> bytes: + encode_data = getattr(msg, msg.which()) + if not self.timing_sei_enabled: + return encode_data.header + encode_data.data + + idx = encode_data.idx + sei_nal = _SEI_PREFIX + struct.pack('>4d', + (idx.timestampEof - idx.timestampSof) / 1e6, + (msg.logMonoTime - idx.timestampEof) / 1e6, + (time.monotonic_ns() - msg.logMonoTime) / 1e6, + time.time() * 1000, # noqa: TID251 + ) + b'\x80' + return encode_data.header + sei_nal + encode_data.data async def recv(self): while True: @@ -30,9 +59,7 @@ class LiveStreamVideoStreamTrack(TiciVideoStreamTrack): break await asyncio.sleep(0.005) - evta = getattr(msg, msg.which()) - - packet = av.Packet(evta.header + evta.data) + packet = av.Packet(self._build_frame_data(msg)) packet.time_base = self._time_base self._pts = ((time.monotonic_ns() - self._t0_ns) * self._clock_rate) // 1_000_000_000 diff --git a/system/webrtc/webrtcd.py b/system/webrtc/webrtcd.py index d2c90cafb5..aac020dd06 100755 --- a/system/webrtc/webrtcd.py +++ b/system/webrtc/webrtcd.py @@ -1,7 +1,11 @@ #!/usr/bin/env python3 +from abc import abstractmethod +import os +import time import argparse import asyncio +import contextlib import json import uuid import logging @@ -19,11 +23,39 @@ if TYPE_CHECKING: from aiortc.rtcdatachannel import RTCDataChannel from openpilot.system.webrtc.schema import generate_field +from openpilot.common.params import Params from cereal import messaging, log -class CerealOutgoingMessageProxy: +class AsyncTaskRunner: + def __init__(self): + self.is_running = False + self.task = None + self.logger = logging.getLogger("webrtcd") + + def start(self): + assert self.task is None + self.task = asyncio.create_task(self.run()) + + async def stop(self): + if self.task is None: + return + task = self.task + self.task = None + if task.done(): + return + task.cancel() + with contextlib.suppress(asyncio.CancelledError): + await task + + @abstractmethod + async def run(self): + pass + + +class CerealOutgoingMessageProxy(AsyncTaskRunner): def __init__(self, sm: messaging.SubMaster): + super().__init__() self.sm = sm self.channels: list[RTCDataChannel] = [] @@ -55,6 +87,19 @@ class CerealOutgoingMessageProxy: for channel in self.channels: channel.send(encoded_msg) + async def run(self): + from aiortc.exceptions import InvalidStateError + + while True: + try: + self.update() + except InvalidStateError: + self.logger.warning("Cereal outgoing proxy invalid state (connection closed)") + break + except Exception: + self.logger.exception("Cereal outgoing proxy failure") + await asyncio.sleep(0.01) + class CerealIncomingMessageProxy: def __init__(self, pm: messaging.PubMaster): @@ -72,37 +117,6 @@ class CerealIncomingMessageProxy: self.pm.send(msg_type, msg) -class CerealProxyRunner: - def __init__(self, proxy: CerealOutgoingMessageProxy): - self.proxy = proxy - self.is_running = False - self.task = None - self.logger = logging.getLogger("webrtcd") - - def start(self): - assert self.task is None - self.task = asyncio.create_task(self.run()) - - def stop(self): - if self.task is None or self.task.done(): - return - self.task.cancel() - self.task = None - - async def run(self): - from aiortc.exceptions import InvalidStateError - - while True: - try: - self.proxy.update() - except InvalidStateError: - self.logger.warning("Cereal outgoing proxy invalid state (connection closed)") - break - except Exception: - self.logger.exception("Cereal outgoing proxy failure") - await asyncio.sleep(0.01) - - class DynamicPubMaster(messaging.PubMaster): def __init__(self, *args, **kwargs): super().__init__(*args, **kwargs) @@ -115,21 +129,90 @@ class DynamicPubMaster(messaging.PubMaster): self.sock[service] = messaging.pub_sock(service) +class LivestreamBitrateController(AsyncTaskRunner): + bitrates = [500_000, 1_500_000, int(os.environ.get("STREAM_BITRATE", 5_000_000))] + label_to_bitrate = { "high": bitrates[2], "med": bitrates[1], "low": bitrates[0]} + sample_interval = 0.2 + high_level = 0.1 # drop immediately + med_level = 0.05 # drop after # of samples + low_level = 0 # raise after # of samples + down_samples = 5 # 1s + param_name = "LivestreamEncoderBitrate" + + def __init__(self, peer_connection: Any): + super().__init__() + self.pc = peer_connection + self.params = Params() + + self.level = 0 + self.prev_lost, self.prev_sent = None, None + self.counter = 0 + self.up_samples = 5 # 1s + self._auto = True + + async def run(self): + while True: + await asyncio.sleep(self.sample_interval) + if not self._auto: + continue + + loss_rate = await self._sample() + if loss_rate is None: + continue + if loss_rate >= self.med_level and self.level > 0: + self.counter += 1 + if self.counter >= self.down_samples or loss_rate >= self.high_level: + self.level -= 1 + self.up_samples *= 2 # exponential backoff before raising again + self.counter = 0 + self._publish(self.bitrates[self.level]) + elif loss_rate <= self.low_level and self.level < len(self.bitrates) - 1: + self.counter -= 1 + if -self.counter >= self.up_samples: + self.level += 1 + self.counter = 0 + self._publish(self.bitrates[self.level]) + + async def _sample(self) -> float | None: + report = await self.pc.getStats() + packets_lost = packets_sent = 0 + for s in report.values(): + if s.type == "remote-inbound-rtp": + packets_lost += s.packetsLost + elif s.type == "outbound-rtp": + packets_sent += s.packetsSent + + if self.prev_lost is None: + self.prev_lost, self.prev_sent = packets_lost, packets_sent + return None + lost_delta = max(0, packets_lost - self.prev_lost) + sent_delta = max(0, packets_sent - self.prev_sent) + self.prev_lost, self.prev_sent = packets_lost, packets_sent + return lost_delta / sent_delta if sent_delta else 0.0 + + def _publish(self, bitrate: float): + self.params.put(self.param_name, bitrate) + + def set_quality(self, quality): + if quality in self.label_to_bitrate: + self._publish(self.label_to_bitrate[quality]) + self._auto = False + elif quality == "auto": + self._auto = True + + class StreamSession: shared_pub_master = DynamicPubMaster([]) - def __init__(self, sdp: str, cameras: list[str], incoming_services: list[str], outgoing_services: list[str], debug_mode: bool = False): + def __init__(self, sdp: str, init_camera: str, incoming_services: list[str], outgoing_services: list[str], debug_mode: bool = False): from aiortc.mediastreams import VideoStreamTrack from openpilot.system.webrtc.device.video import LiveStreamVideoStreamTrack from teleoprtc import WebRTCAnswerBuilder - from teleoprtc.info import parse_info_from_offer - config = parse_info_from_offer(sdp) builder = WebRTCAnswerBuilder(sdp) - assert len(cameras) == config.n_expected_camera_tracks, "Incoming stream has misconfigured number of video tracks" - for cam in cameras: - builder.add_video_stream(cam, LiveStreamVideoStreamTrack(cam) if not debug_mode else VideoStreamTrack()) + self.video_track = LiveStreamVideoStreamTrack(init_camera) if not debug_mode else VideoStreamTrack() + builder.add_video_stream(init_camera, self.video_track) self.stream = builder.stream() self.identifier = str(uuid.uuid4()) @@ -137,35 +220,60 @@ class StreamSession: self.incoming_bridge: CerealIncomingMessageProxy | None = None self.incoming_bridge_services = incoming_services self.outgoing_bridge: CerealOutgoingMessageProxy | None = None - self.outgoing_bridge_runner: CerealProxyRunner | None = None + self.bitrate_controller: LivestreamBitrateController | None = None if len(incoming_services) > 0: self.incoming_bridge = CerealIncomingMessageProxy(self.shared_pub_master) if len(outgoing_services) > 0: self.outgoing_bridge = CerealOutgoingMessageProxy(messaging.SubMaster(outgoing_services)) - self.outgoing_bridge_runner = CerealProxyRunner(self.outgoing_bridge) + self.bitrate_controller = LivestreamBitrateController(self.stream.peer_connection) self.run_task: asyncio.Task | None = None + self._cleanup_lock = asyncio.Lock() + self._cleanup_done = False self.logger = logging.getLogger("webrtcd") - self.logger.info("New stream session (%s), cameras %s, incoming services %s, outgoing services %s", - self.identifier, cameras, incoming_services, outgoing_services) + self.logger.info( + "New stream session (%s), init camera %s, incoming services %s, outgoing services %s", + self.identifier, init_camera, incoming_services, outgoing_services, + ) def start(self): self.run_task = asyncio.create_task(self.run()) - def stop(self): - if self.run_task.done(): - return - self.run_task.cancel() + async def stop(self): + if self.run_task is not None and not self.run_task.done() and self.run_task is not asyncio.current_task(): + self.run_task.cancel() + with contextlib.suppress(asyncio.CancelledError): + await self.run_task self.run_task = None - asyncio.run(self.post_run_cleanup()) + await self.post_run_cleanup() async def get_answer(self): return await self.stream.start() - async def message_handler(self, message: bytes): + def message_handler(self, message: bytes): assert self.incoming_bridge is not None try: - self.incoming_bridge.send(message) + payload = json.loads(message) if isinstance(message, (bytes, str)) else None + if isinstance(payload, dict): + msg_type = payload.get("type") + + match msg_type: + case "livestreamCameraSwitch": + self.video_track.switch_camera(payload["data"]["camera"]) + case "livestreamSettings": + self.bitrate_controller.set_quality(payload["data"]["quality"]) + case "clockSync": + pong = json.dumps({"type": "clockSync", "data": { + "action": "pong", "browserSendTime": payload["data"]["browserSendTime"], "deviceTime": time.time() * 1000, # noqa: TID251 + }}) + self.stream.get_messaging_channel().send(pong) + case "enableTimingSei": + if hasattr(self.video_track, 'timing_sei_enabled'): + self.video_track.timing_sei_enabled = bool(payload["data"]["enabled"]) + case _: + if payload.get("type") not in self.incoming_bridge_services: + return + self.incoming_bridge.send(message) except Exception: self.logger.exception("Cereal incoming proxy failure") @@ -176,29 +284,38 @@ class StreamSession: if self.incoming_bridge is not None: await self.shared_pub_master.add_services_if_needed(self.incoming_bridge_services) self.stream.set_message_handler(self.message_handler) - if self.outgoing_bridge_runner is not None: + if self.outgoing_bridge is not None: channel = self.stream.get_messaging_channel() - self.outgoing_bridge_runner.proxy.add_channel(channel) - self.outgoing_bridge_runner.start() + self.outgoing_bridge.add_channel(channel) + self.outgoing_bridge.start() + self.bitrate_controller.start() + self.logger.info("Stream session (%s) connected", self.identifier) await self.stream.wait_for_disconnection() - await self.post_run_cleanup() self.logger.info("Stream session (%s) ended", self.identifier) except Exception: self.logger.exception("Stream session failure") + finally: + await self.post_run_cleanup() async def post_run_cleanup(self): - await self.stream.stop() - if self.outgoing_bridge is not None: - self.outgoing_bridge_runner.stop() + async with self._cleanup_lock: + if self._cleanup_done: + return + self._cleanup_done = True + if self.bitrate_controller is not None: + await self.bitrate_controller.stop() + if self.outgoing_bridge is not None: + await self.outgoing_bridge.stop() + await self.stream.stop() @dataclass class StreamRequestBody: sdp: str - cameras: list[str] + initCamera: str bridge_services_in: list[str] = field(default_factory=list) bridge_services_out: list[str] = field(default_factory=list) @@ -208,11 +325,33 @@ async def get_stream(request: 'web.Request'): raw_body = await request.json() body = StreamRequestBody(**raw_body) - session = StreamSession(body.sdp, body.cameras, body.bridge_services_in, body.bridge_services_out, debug_mode) - answer = await session.get_answer() - session.start() + async with request.app['stream_lock']: + # Fully disconnect any other active stream before starting the replacement. + for sid, s in list(stream_dict.items()): + if s.run_task and not s.run_task.done(): + try: + ch = s.stream.get_messaging_channel() + ch.send(json.dumps({"type": "connectionReplaced", "data": "Another device has connected, closing this session."})) + except Exception: + pass + await s.stop() + del stream_dict[sid] - stream_dict[session.identifier] = session + session = StreamSession(body.sdp, body.initCamera, body.bridge_services_in, body.bridge_services_out, debug_mode) + try: + answer = await session.get_answer() + except ValueError as e: + await session.stop() + raise web.HTTPBadRequest( + text=json.dumps({"error": "invalid_sdp", "message": str(e)}), + content_type="application/json", + ) from e + except Exception: + await session.stop() + raise + session.start() + + stream_dict[session.identifier] = session return web.json_response({"sdp": answer.sdp, "type": answer.type}) @@ -224,6 +363,7 @@ async def get_schema(request: 'web.Request'): schema_dict = {s: generate_field(log.Event.schema.fields[s]) for s in services} return web.json_response(schema_dict) + async def post_notify(request: 'web.Request'): try: payload = await request.json() @@ -239,9 +379,10 @@ async def post_notify(request: 'web.Request'): return web.Response(status=200, text="OK") + async def on_shutdown(app: 'web.Application'): for session in app['streams'].values(): - session.stop() + await session.stop() del app['streams'] @@ -254,6 +395,7 @@ def webrtcd_thread(host: str, port: int, debug: bool): app = web.Application() app['streams'] = dict() + app['stream_lock'] = asyncio.Lock() app['debug'] = debug app.on_shutdown.append(on_shutdown) app.router.add_post("/stream", get_stream) diff --git a/teleoprtc_repo b/teleoprtc_repo index 389815b8ca..22df577821 160000 --- a/teleoprtc_repo +++ b/teleoprtc_repo @@ -1 +1 @@ -Subproject commit 389815b8ca5302ce7c1504b7841d4eb61a8cd51b +Subproject commit 22df577821862e32a011fb0cf42577599f3a79c4 diff --git a/third_party/SConscript b/third_party/SConscript deleted file mode 100644 index 3a7497d162..0000000000 --- a/third_party/SConscript +++ /dev/null @@ -1,3 +0,0 @@ -Import('env') - -env.Library('json11', ['json11/json11.cpp'], CCFLAGS=env['CCFLAGS'] + ['-Wno-unqualified-std-cast-call']) diff --git a/third_party/acados/.gitignore b/third_party/acados/.gitignore deleted file mode 100644 index 0ae664dff6..0000000000 --- a/third_party/acados/.gitignore +++ /dev/null @@ -1,9 +0,0 @@ -acados_repo/ -/lib -!x86_64/ -!larch64/ -!aarch64/ -!Darwin/ -!*.so -!*.so.* -!*.dylib diff --git a/third_party/acados/Darwin/lib/libacados.dylib b/third_party/acados/Darwin/lib/libacados.dylib deleted file mode 100755 index 8cd5a41f14..0000000000 --- a/third_party/acados/Darwin/lib/libacados.dylib +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:620195ff61aaccf9adf00a66b8acf4e9915a0895d0a86f9f51ec952e44fad70a -size 853776 diff --git a/third_party/acados/Darwin/lib/libblasfeo.dylib b/third_party/acados/Darwin/lib/libblasfeo.dylib deleted file mode 100755 index 442a6c736d..0000000000 --- a/third_party/acados/Darwin/lib/libblasfeo.dylib +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:1d9dbeb68b2ac13c884f606a1f6032f399640e0928cecad4c22b700a8d8ae970 -size 2010877 diff --git a/third_party/acados/Darwin/lib/libhpipm.dylib b/third_party/acados/Darwin/lib/libhpipm.dylib deleted file mode 100755 index 019ec8019e..0000000000 --- a/third_party/acados/Darwin/lib/libhpipm.dylib +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:35783dba64c2d5bbe7e4c98ad01accac56b478b1bf874969ab5c31d7495499a2 -size 2290624 diff --git a/third_party/acados/Darwin/lib/libqpOASES_e.3.1.dylib b/third_party/acados/Darwin/lib/libqpOASES_e.3.1.dylib deleted file mode 100755 index caaa8ec775..0000000000 --- a/third_party/acados/Darwin/lib/libqpOASES_e.3.1.dylib +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:f57eea51f4b91deff47fbf599eedc3eafedd395f23465b5fb24b2148fdaa2859 -size 496707 diff --git a/third_party/acados/Darwin/lib/libqpOASES_e.dylib b/third_party/acados/Darwin/lib/libqpOASES_e.dylib deleted file mode 120000 index e3d94c4bc2..0000000000 --- a/third_party/acados/Darwin/lib/libqpOASES_e.dylib +++ /dev/null @@ -1 +0,0 @@ -libqpOASES_e.3.1.dylib \ No newline at end of file diff --git a/third_party/acados/Darwin/t_renderer b/third_party/acados/Darwin/t_renderer deleted file mode 100755 index 83a74ea5a3..0000000000 --- a/third_party/acados/Darwin/t_renderer +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:c6c78791cfdd841da14266c62a6099d0af53cec348051118f1a70518729aa5ba -size 8483768 diff --git a/third_party/acados/aarch64 b/third_party/acados/aarch64 deleted file mode 120000 index 062c65e8d9..0000000000 --- a/third_party/acados/aarch64 +++ /dev/null @@ -1 +0,0 @@ -larch64/ \ No newline at end of file diff --git a/third_party/acados/acados_template/.gitignore b/third_party/acados/acados_template/.gitignore deleted file mode 100644 index 63b741bb9d..0000000000 --- a/third_party/acados/acados_template/.gitignore +++ /dev/null @@ -1,6 +0,0 @@ -__pycache__/ - -# Cython intermediates -*_pyx.c -*_pyx.o -*_pyx.so diff --git a/third_party/acados/acados_template/__init__.py b/third_party/acados/acados_template/__init__.py deleted file mode 100644 index bfbe907990..0000000000 --- a/third_party/acados/acados_template/__init__.py +++ /dev/null @@ -1,40 +0,0 @@ -# -# Copyright (c) The acados authors. -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# - -from .acados_model import AcadosModel -from .acados_ocp import AcadosOcp, AcadosOcpConstraints, AcadosOcpCost, AcadosOcpDims, AcadosOcpOptions -from .acados_sim import AcadosSim, AcadosSimDims, AcadosSimOpts -from .acados_ocp_solver import AcadosOcpSolver, get_simulink_default_opts, ocp_get_default_cmake_builder -from .acados_sim_solver import AcadosSimSolver, sim_get_default_cmake_builder -from .utils import print_casadi_expression, get_acados_path, get_python_interface_path, \ - get_tera_exec_path, get_tera, check_casadi_version, acados_dae_model_json_dump, \ - casadi_length, make_object_json_dumpable, J_to_idx, get_default_simulink_opts - -from .zoro_description import ZoroDescription, process_zoro_description diff --git a/third_party/acados/acados_template/acados_layout.json b/third_party/acados/acados_template/acados_layout.json deleted file mode 100644 index a1cc5bbdf3..0000000000 --- a/third_party/acados/acados_template/acados_layout.json +++ /dev/null @@ -1,834 +0,0 @@ -{ - "code_export_directory": [ - "str" - ], - "acados_include_path": [ - "str" - ], - "cython_include_dirs": [ - "list" - ], - "json_file": [ - "str" - ], - "shared_lib_ext": [ - "str" - ], - "model": { - "name" : [ - "str" - ], - "dyn_ext_fun_type" : [ - "str" - ], - "dyn_generic_source" : [ - "str" - ], - "dyn_impl_dae_fun" : [ - "str" - ], - "dyn_impl_dae_fun_jac" : [ - "str" - ], - "dyn_impl_dae_jac" : [ - "str" - ], - "dyn_disc_fun_jac_hess" : [ - "str" - ], - "dyn_disc_fun_jac" : [ - "str" - ], - "dyn_disc_fun" : [ - "str" - ], - "gnsf" : { - "nontrivial_f_LO": [ - "int" - ], - "purely_linear": [ - "int" - ] - } - }, - "parameter_values": [ - "ndarray", - [ - "np" - ] - ], - "acados_lib_path": [ - "str" - ], - "problem_class": [ - "str" - ], - "constraints": { - "constr_type": [ - "str" - ], - "constr_type_e": [ - "str" - ], - "lbx": [ - "ndarray", - [ - "nbx" - ] - ], - "lbu": [ - "ndarray", - [ - "nbu" - ] - ], - "ubx": [ - "ndarray", - [ - "nbx" - ] - ], - "ubu": [ - "ndarray", - [ - "nbu" - ] - ], - "idxbx": [ - "ndarray", - [ - "nbx" - ] - ], - "idxbu": [ - "ndarray", - [ - "nbu" - ] - ], - "lbx_e": [ - "ndarray", - [ - "nbx_e" - ] - ], - "ubx_e": [ - "ndarray", - [ - "nbx_e" - ] - ], - "idxbx_e": [ - "ndarray", - [ - "nbx_e" - ] - ], - "lbx_0": [ - "ndarray", - [ - "nbx_0" - ] - ], - "ubx_0": [ - "ndarray", - [ - "nbx_0" - ] - ], - "idxbx_0": [ - "ndarray", - [ - "nbx_0" - ] - ], - "idxbxe_0": [ - "ndarray", - [ - "nbxe_0" - ] - ], - "lg": [ - "ndarray", - [ - "ng" - ] - ], - "ug": [ - "ndarray", - [ - "ng" - ] - ], - "D": [ - "ndarray", - [ - "ng", - "nu" - ] - ], - "C": [ - "ndarray", - [ - "ng", - "nx" - ] - ], - "C_e": [ - "ndarray", - [ - "ng_e", - "nx" - ] - ], - "lg_e": [ - "ndarray", - [ - "ng_e" - ] - ], - "ug_e": [ - "ndarray", - [ - "ng_e" - ] - ], - "lh": [ - "ndarray", - [ - "nh" - ] - ], - "uh": [ - "ndarray", - [ - "nh" - ] - ], - "lh_e": [ - "ndarray", - [ - "nh_e" - ] - ], - "uh_e": [ - "ndarray", - [ - "nh_e" - ] - ], - "lphi": [ - "ndarray", - [ - "nphi" - ] - ], - "uphi": [ - "ndarray", - [ - "nphi" - ] - ], - "lphi_e": [ - "ndarray", - [ - "nphi_e" - ] - ], - "uphi_e": [ - "ndarray", - [ - "nphi_e" - ] - ], - "lsbx": [ - "ndarray", - [ - "nsbx" - ] - ], - "usbx": [ - "ndarray", - [ - "nsbx" - ] - ], - "lsbu": [ - "ndarray", - [ - "nsbu" - ] - ], - "usbu": [ - "ndarray", - [ - "nsbu" - ] - ], - "idxsbx": [ - "ndarray", - [ - "nsbx" - ] - ], - "idxsbu": [ - "ndarray", - [ - "nsbu" - ] - ], - "lsbx_e": [ - "ndarray", - [ - "nsbx_e" - ] - ], - "usbx_e": [ - "ndarray", - [ - "nsbx_e" - ] - ], - "idxsbx_e": [ - "ndarray", - [ - "nsbx_e" - ] - ], - "lsg": [ - "ndarray", - [ - "nsg" - ] - ], - "usg": [ - "ndarray", - [ - "nsg" - ] - ], - "idxsg": [ - "ndarray", - [ - "nsg" - ] - ], - "lsg_e": [ - "ndarray", - [ - "nsg_e" - ] - ], - "usg_e": [ - "ndarray", - [ - "nsg_e" - ] - ], - "idxsg_e": [ - "ndarray", - [ - "nsg_e" - ] - ], - "lsh": [ - "ndarray", - [ - "nsh" - ] - ], - "ush": [ - "ndarray", - [ - "nsh" - ] - ], - "idxsh": [ - "ndarray", - [ - "nsh" - ] - ], - "lsh_e": [ - "ndarray", - [ - "nsh_e" - ] - ], - "ush_e": [ - "ndarray", - [ - "nsh_e" - ] - ], - "idxsh_e": [ - "ndarray", - [ - "nsh_e" - ] - ], - "lsphi": [ - "ndarray", - [ - "nsphi" - ] - ], - "usphi": [ - "ndarray", - [ - "nsphi" - ] - ], - "idxsphi": [ - "ndarray", - [ - "nsphi" - ] - ], - "lsphi_e": [ - "ndarray", - [ - "nsphi_e" - ] - ], - "usphi_e": [ - "ndarray", - [ - "nsphi_e" - ] - ], - "idxsphi_e": [ - "ndarray", - [ - "nsphi_e" - ] - ] - }, - "cost": { - "cost_type_0": [ - "str" - ], - "cost_type": [ - "str" - ], - "cost_type_e": [ - "str" - ], - "cost_ext_fun_type_0": [ - "str" - ], - "cost_ext_fun_type": [ - "str" - ], - "cost_ext_fun_type_e": [ - "str" - ], - "Vu_0": [ - "ndarray", - [ - "ny_0", - "nu" - ] - ], - "Vu": [ - "ndarray", - [ - "ny", - "nu" - ] - ], - "Vx_0": [ - "ndarray", - [ - "ny_0", - "nx" - ] - ], - "Vx": [ - "ndarray", - [ - "ny", - "nx" - ] - ], - "Vx_e": [ - "ndarray", - [ - "ny_e", - "nx" - ] - ], - "Vz_0": [ - "ndarray", - [ - "ny_0", - "nz" - ] - ], - "Vz": [ - "ndarray", - [ - "ny", - "nz" - ] - ], - "W_0": [ - "ndarray", - [ - "ny_0", - "ny_0" - ] - ], - "W": [ - "ndarray", - [ - "ny", - "ny" - ] - ], - "Zl": [ - "ndarray", - [ - "ns" - ] - ], - "Zu": [ - "ndarray", - [ - "ns" - ] - ], - "zl": [ - "ndarray", - [ - "ns" - ] - ], - "zu": [ - "ndarray", - [ - "ns" - ] - ], - "W_e": [ - "ndarray", - [ - "ny_e", - "ny_e" - ] - ], - "yref_0": [ - "ndarray", - [ - "ny_0" - ] - ], - "yref": [ - "ndarray", - [ - "ny" - ] - ], - "yref_e": [ - "ndarray", - [ - "ny_e" - ] - ], - "Zl_e": [ - "ndarray", - [ - "ns_e" - ] - ], - "Zu_e": [ - "ndarray", - [ - "ns_e" - ] - ], - "zl_e": [ - "ndarray", - [ - "ns_e" - ] - ], - "zu_e": [ - "ndarray", - [ - "ns_e" - ] - ] - }, - "dims": { - "N": [ - "int" - ], - "nbu": [ - "int" - ], - "nbx": [ - "int" - ], - "nsbu": [ - "int" - ], - "nsbx": [ - "int" - ], - "nsbx_e": [ - "int" - ], - "nbx_0": [ - "int" - ], - "nbx_e": [ - "int" - ], - "nbxe_0": [ - "int" - ], - "nsg": [ - "int" - ], - "nsg_e": [ - "int" - ], - "nsh": [ - "int" - ], - "nsh_e": [ - "int" - ], - "nsphi": [ - "int" - ], - "nsphi_e": [ - "int" - ], - "ns": [ - "int" - ], - "ns_e": [ - "int" - ], - "ng": [ - "int" - ], - "ng_e": [ - "int" - ], - "np": [ - "int" - ], - "nr": [ - "int" - ], - "nr_e": [ - "int" - ], - "nh": [ - "int" - ], - "nh_e": [ - "int" - ], - "nphi": [ - "int" - ], - "nphi_e": [ - "int" - ], - "nu": [ - "int" - ], - "nx": [ - "int" - ], - "ny": [ - "int" - ], - "ny_0": [ - "int" - ], - "ny_e": [ - "int" - ], - "nz": [ - "int" - ], - "gnsf_nx1": [ - "int" - ], - "gnsf_nz1": [ - "int" - ], - "gnsf_nuhat": [ - "int" - ], - "gnsf_ny": [ - "int" - ], - "gnsf_nout": [ - "int" - ] - }, - "solver_options": { - "time_steps": [ - "ndarray", - [ - "N" - ] - ], - "hessian_approx": [ - "str" - ], - "hpipm_mode": [ - "str" - ], - "regularize_method": [ - "str" - ], - "integrator_type": [ - "str" - ], - "nlp_solver_type": [ - "str" - ], - "collocation_type": [ - "str" - ], - "globalization": [ - "str" - ], - "nlp_solver_step_length": [ - "float" - ], - "levenberg_marquardt": [ - "float" - ], - "qp_solver": [ - "str" - ], - "tf": [ - "float" - ], - "Tsim": [ - "float" - ], - "alpha_min": [ - "float" - ], - "alpha_reduction": [ - "float" - ], - "line_search_use_sufficient_descent": [ - "int" - ], - "globalization_use_SOC": [ - "int" - ], - "full_step_dual": [ - "int" - ], - "eps_sufficient_descent": [ - "float" - ], - "sim_method_num_stages": [ - "ndarray", - [ - "N" - ] - ], - "sim_method_num_steps": [ - "ndarray", - [ - "N" - ] - ], - "sim_method_newton_iter": [ - "int" - ], - "sim_method_newton_tol": [ - "float" - ], - "sim_method_jac_reuse": [ - "ndarray", - [ - "N" - ] - ], - "qp_solver_cond_N": [ - "int" - ], - "qp_solver_warm_start": [ - "int" - ], - "qp_solver_tol_stat": [ - "float" - ], - "qp_solver_tol_eq": [ - "float" - ], - "qp_solver_tol_ineq": [ - "float" - ], - "qp_solver_tol_comp": [ - "float" - ], - "qp_solver_iter_max": [ - "int" - ], - "qp_solver_cond_ric_alg": [ - "int" - ], - "qp_solver_ric_alg": [ - "int" - ], - "nlp_solver_tol_stat": [ - "float" - ], - "nlp_solver_tol_eq": [ - "float" - ], - "nlp_solver_tol_ineq": [ - "float" - ], - "nlp_solver_tol_comp": [ - "float" - ], - "nlp_solver_max_iter": [ - "int" - ], - "nlp_solver_ext_qp_res": [ - "int" - ], - "print_level": [ - "int" - ], - "initialize_t_slacks": [ - "int" - ], - "exact_hess_cost": [ - "int" - ], - "exact_hess_constr": [ - "int" - ], - "exact_hess_dyn": [ - "int" - ], - "ext_cost_num_hess": [ - "int" - ], - "ext_fun_compile_flags": [ - "str" - ], - "model_external_shared_lib_dir": [ - "str" - ], - "model_external_shared_lib_name": [ - "str" - ] - } -} diff --git a/third_party/acados/acados_template/acados_model.py b/third_party/acados/acados_template/acados_model.py deleted file mode 100644 index b7c6945442..0000000000 --- a/third_party/acados/acados_template/acados_model.py +++ /dev/null @@ -1,154 +0,0 @@ -# -# Copyright (c) The acados authors. -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# - - -class AcadosModel(): - """ - Class containing all the information to code generate the external CasADi functions - that are needed when creating an acados ocp solver or acados integrator. - Thus, this class contains: - - a) the :py:attr:`name` of the model, - b) all CasADi variables/expressions needed in the CasADi function generation process. - """ - def __init__(self): - ## common for OCP and Integrator - self.name = None - """ - The model name is used for code generation. Type: string. Default: :code:`None` - """ - self.x = None #: CasADi variable describing the state of the system; Default: :code:`None` - self.xdot = None #: CasADi variable describing the derivative of the state wrt time; Default: :code:`None` - self.u = None #: CasADi variable describing the input of the system; Default: :code:`None` - self.z = [] #: CasADi variable describing the algebraic variables of the DAE; Default: :code:`empty` - self.p = [] #: CasADi variable describing parameters of the DAE; Default: :code:`empty` - # dynamics - self.f_impl_expr = None - """ - CasADi expression for the implicit dynamics :math:`f_\\text{impl}(\dot{x}, x, u, z, p) = 0`. - Used if :py:attr:`acados_template.acados_ocp.AcadosOcpOptions.integrator_type` == 'IRK'. - Default: :code:`None` - """ - self.f_expl_expr = None - """ - CasADi expression for the explicit dynamics :math:`\dot{x} = f_\\text{expl}(x, u, p)`. - Used if :py:attr:`acados_template.acados_ocp.AcadosOcpOptions.integrator_type` == 'ERK'. - Default: :code:`None` - """ - self.disc_dyn_expr = None - """ - CasADi expression for the discrete dynamics :math:`x_{+} = f_\\text{disc}(x, u, p)`. - Used if :py:attr:`acados_template.acados_ocp.AcadosOcpOptions.integrator_type` == 'DISCRETE'. - Default: :code:`None` - """ - - self.dyn_ext_fun_type = 'casadi' #: type of external functions for dynamics module; 'casadi' or 'generic'; Default: 'casadi' - self.dyn_generic_source = None #: name of source file for discrete dyanamics; Default: :code:`None` - self.dyn_disc_fun_jac_hess = None #: name of function discrete dyanamics + jacobian and hessian; Default: :code:`None` - self.dyn_disc_fun_jac = None #: name of function discrete dyanamics + jacobian; Default: :code:`None` - self.dyn_disc_fun = None #: name of function discrete dyanamics; Default: :code:`None` - - # for GNSF models - self.gnsf = {'nontrivial_f_LO': 1, 'purely_linear': 0} - """ - dictionary containing information on GNSF structure needed when rendering templates. - Contains integers `nontrivial_f_LO`, `purely_linear`. - """ - - ## for OCP - # constraints - # BGH(default): lh <= h(x, u) <= uh - self.con_h_expr = None #: CasADi expression for the constraint :math:`h`; Default: :code:`None` - # BGP(convex over nonlinear): lphi <= phi(r(x, u)) <= uphi - self.con_phi_expr = None #: CasADi expression for the constraint phi; Default: :code:`None` - self.con_r_expr = None #: CasADi expression for the constraint phi(r); Default: :code:`None` - self.con_r_in_phi = None - # terminal - self.con_h_expr_e = None #: CasADi expression for the terminal constraint :math:`h^e`; Default: :code:`None` - self.con_r_expr_e = None #: CasADi expression for the terminal constraint; Default: :code:`None` - self.con_phi_expr_e = None #: CasADi expression for the terminal constraint; Default: :code:`None` - self.con_r_in_phi_e = None - # cost - self.cost_y_expr = None #: CasADi expression for nonlinear least squares; Default: :code:`None` - self.cost_y_expr_e = None #: CasADi expression for nonlinear least squares, terminal; Default: :code:`None` - self.cost_y_expr_0 = None #: CasADi expression for nonlinear least squares, initial; Default: :code:`None` - self.cost_expr_ext_cost = None #: CasADi expression for external cost; Default: :code:`None` - self.cost_expr_ext_cost_e = None #: CasADi expression for external cost, terminal; Default: :code:`None` - self.cost_expr_ext_cost_0 = None #: CasADi expression for external cost, initial; Default: :code:`None` - self.cost_expr_ext_cost_custom_hess = None #: CasADi expression for custom hessian (only for external cost); Default: :code:`None` - self.cost_expr_ext_cost_custom_hess_e = None #: CasADi expression for custom hessian (only for external cost), terminal; Default: :code:`None` - self.cost_expr_ext_cost_custom_hess_0 = None #: CasADi expression for custom hessian (only for external cost), initial; Default: :code:`None` - - ## CONVEX_OVER_NONLINEAR convex-over-nonlinear cost: psi(y(x, u, p) - y_ref; p) - self.cost_psi_expr_0 = None - """ - CasADi expression for the outer loss function :math:`\psi(r, p)`, initial; Default: :code:`None` - Used if :py:attr:`acados_template.acados_ocp.AcadosOcpOptions.cost_type_0` == 'CONVEX_OVER_NONLINEAR'. - """ - self.cost_psi_expr = None - """ - CasADi expression for the outer loss function :math:`\psi(r, p)`; Default: :code:`None` - Used if :py:attr:`acados_template.acados_ocp.AcadosOcpOptions.cost_type` == 'CONVEX_OVER_NONLINEAR'. - """ - self.cost_psi_expr_e = None - """ - CasADi expression for the outer loss function :math:`\psi(r, p)`, terminal; Default: :code:`None` - Used if :py:attr:`acados_template.acados_ocp.AcadosOcpOptions.cost_type_e` == 'CONVEX_OVER_NONLINEAR'. - """ - self.cost_r_in_psi_expr_0 = None - """ - CasADi expression for the argument :math:`r`; to the outer loss function :math:`\psi(r, p)`, initial; Default: :code:`None` - Used if :py:attr:`acados_template.acados_ocp.AcadosOcpOptions.cost_type_0` == 'CONVEX_OVER_NONLINEAR'. - """ - self.cost_r_in_psi_expr = None - """ - CasADi expression for the argument :math:`r`; to the outer loss function :math:`\psi(r, p)`; Default: :code:`None` - Used if :py:attr:`acados_template.acados_ocp.AcadosOcpOptions.cost_type` == 'CONVEX_OVER_NONLINEAR'. - """ - self.cost_r_in_psi_expr_e = None - """ - CasADi expression for the argument :math:`r`; to the outer loss function :math:`\psi(r, p)`, terminal; Default: :code:`None` - Used if :py:attr:`acados_template.acados_ocp.AcadosOcpOptions.cost_type_e` == 'CONVEX_OVER_NONLINEAR'. - """ - self.cost_conl_custom_outer_hess_0 = None - """ - CasADi expression for the custom hessian of the outer loss function (only for convex-over-nonlinear cost), initial; Default: :code:`None` - Used if :py:attr:`acados_template.acados_ocp.AcadosOcpOptions.cost_type_0` == 'CONVEX_OVER_NONLINEAR'. - """ - self.cost_conl_custom_outer_hess = None - """ - CasADi expression for the custom hessian of the outer loss function (only for convex-over-nonlinear cost); Default: :code:`None` - Used if :py:attr:`acados_template.acados_ocp.AcadosOcpOptions.cost_type` == 'CONVEX_OVER_NONLINEAR'. - """ - self.cost_conl_custom_outer_hess_e = None - """ - CasADi expression for the custom hessian of the outer loss function (only for convex-over-nonlinear cost), terminal; Default: :code:`None` - Used if :py:attr:`acados_template.acados_ocp.AcadosOcpOptions.cost_type_e` == 'CONVEX_OVER_NONLINEAR'. - """ diff --git a/third_party/acados/acados_template/acados_ocp.py b/third_party/acados/acados_template/acados_ocp.py deleted file mode 100644 index d6236e1f6e..0000000000 --- a/third_party/acados/acados_template/acados_ocp.py +++ /dev/null @@ -1,3166 +0,0 @@ -# -# Copyright (c) The acados authors. -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# - -import numpy as np -import os -from .acados_model import AcadosModel -from .utils import get_acados_path, J_to_idx, J_to_idx_slack, get_lib_ext - -class AcadosOcpDims: - """ - Class containing the dimensions of the optimal control problem. - """ - def __init__(self): - self.__nx = None - self.__nu = None - self.__nz = 0 - self.__np = 0 - self.__ny = 0 - self.__ny_e = 0 - self.__ny_0 = 0 - self.__nr = 0 - self.__nr_e = 0 - self.__nh = 0 - self.__nh_e = 0 - self.__nphi = 0 - self.__nphi_e = 0 - self.__nbx = 0 - self.__nbx_0 = 0 - self.__nbx_e = 0 - self.__nbu = 0 - self.__nsbx = 0 - self.__nsbx_e = 0 - self.__nsbu = 0 - self.__nsh = 0 - self.__nsh_e = 0 - self.__nsphi = 0 - self.__nsphi_e = 0 - self.__ns = 0 - self.__ns_e = 0 - self.__ng = 0 - self.__ng_e = 0 - self.__nsg = 0 - self.__nsg_e = 0 - self.__nbxe_0 = None - self.__N = None - - - @property - def nx(self): - """:math:`n_x` - number of states. - Type: int; default: None""" - return self.__nx - - @property - def nz(self): - """:math:`n_z` - number of algebraic variables. - Type: int; default: 0""" - return self.__nz - - @property - def nu(self): - """:math:`n_u` - number of inputs. - Type: int; default: None""" - return self.__nu - - @property - def np(self): - """:math:`n_p` - number of parameters. - Type: int; default: 0""" - return self.__np - - @property - def ny(self): - """:math:`n_y` - number of residuals in Lagrange term. - Type: int; default: 0""" - return self.__ny - - @property - def ny_0(self): - """:math:`n_{y}^0` - number of residuals in Mayer term. - Type: int; default: 0""" - return self.__ny_0 - - @property - def ny_e(self): - """:math:`n_{y}^e` - number of residuals in Mayer term. - Type: int; default: 0""" - return self.__ny_e - - @property - def nr(self): - """:math:`n_{\pi}` - dimension of the image of the inner nonlinear function in positive definite constraints. - Type: int; default: 0""" - return self.__nr - - @property - def nr_e(self): - """:math:`n_{\pi}^e` - dimension of the image of the inner nonlinear function in positive definite constraints. - Type: int; default: 0""" - return self.__nr_e - - @property - def nh(self): - """:math:`n_h` - number of nonlinear constraints. - Type: int; default: 0""" - return self.__nh - - @property - def nh_e(self): - """:math:`n_{h}^e` - number of nonlinear constraints at terminal shooting node N. - Type: int; default: 0""" - return self.__nh_e - - @property - def nphi(self): - """:math:`n_{\phi}` - number of convex-over-nonlinear constraints. - Type: int; default: 0""" - return self.__nphi - - @property - def nphi_e(self): - """:math:`n_{\phi}^e` - number of convex-over-nonlinear constraints at terminal shooting node N. - Type: int; default: 0""" - return self.__nphi_e - - @property - def nbx(self): - """:math:`n_{b_x}` - number of state bounds. - Type: int; default: 0""" - return self.__nbx - - @property - def nbxe_0(self): - """:math:`n_{be_{x0}}` - number of state bounds at initial shooting node that are equalities. - Type: int; default: None""" - return self.__nbxe_0 - - @property - def nbx_0(self): - """:math:`n_{b_{x0}}` - number of state bounds for initial state. - Type: int; default: 0""" - return self.__nbx_0 - - @property - def nbx_e(self): - """:math:`n_{b_x}` - number of state bounds at terminal shooting node N. - Type: int; default: 0""" - return self.__nbx_e - - @property - def nbu(self): - """:math:`n_{b_u}` - number of input bounds. - Type: int; default: 0""" - return self.__nbu - - @property - def nsbx(self): - """:math:`n_{{sb}_x}` - number of soft state bounds. - Type: int; default: 0""" - return self.__nsbx - - @property - def nsbx_e(self): - """:math:`n_{{sb}^e_{x}}` - number of soft state bounds at terminal shooting node N. - Type: int; default: 0""" - return self.__nsbx_e - - @property - def nsbu(self): - """:math:`n_{{sb}_u}` - number of soft input bounds. - Type: int; default: 0""" - return self.__nsbu - - @property - def nsg(self): - """:math:`n_{{sg}}` - number of soft general linear constraints. - Type: int; default: 0""" - return self.__nsg - - @property - def nsg_e(self): - """:math:`n_{{sg}^e}` - number of soft general linear constraints at terminal shooting node N. - Type: int; default: 0""" - return self.__nsg_e - - @property - def nsh(self): - """:math:`n_{{sh}}` - number of soft nonlinear constraints. - Type: int; default: 0""" - return self.__nsh - - @property - def nsh_e(self): - """:math:`n_{{sh}}^e` - number of soft nonlinear constraints at terminal shooting node N. - Type: int; default: 0""" - return self.__nsh_e - - @property - def nsphi(self): - """:math:`n_{{s\phi}}` - number of soft convex-over-nonlinear constraints. - Type: int; default: 0""" - return self.__nsphi - - @property - def nsphi_e(self): - """:math:`n_{{s\phi}^e}` - number of soft convex-over-nonlinear constraints at terminal shooting node N. - Type: int; default: 0""" - return self.__nsphi_e - - @property - def ns(self): - """:math:`n_{s}` - total number of slacks. - Type: int; default: 0""" - return self.__ns - - @property - def ns_e(self): - """:math:`n_{s}^e` - total number of slacks at terminal shooting node N. - Type: int; default: 0""" - return self.__ns_e - - @property - def ng(self): - """:math:`n_{g}` - number of general polytopic constraints. - Type: int; default: 0""" - return self.__ng - - @property - def ng_e(self): - """:math:`n_{g}^e` - number of general polytopic constraints at terminal shooting node N. - Type: int; default: 0""" - return self.__ng_e - - @property - def N(self): - """:math:`N` - prediction horizon. - Type: int; default: None""" - return self.__N - - @nx.setter - def nx(self, nx): - if isinstance(nx, int) and nx > 0: - self.__nx = nx - else: - raise Exception('Invalid nx value, expected positive integer.') - - @nz.setter - def nz(self, nz): - if isinstance(nz, int) and nz > -1: - self.__nz = nz - else: - raise Exception('Invalid nz value, expected nonnegative integer.') - - @nu.setter - def nu(self, nu): - if isinstance(nu, int) and nu > -1: - self.__nu = nu - else: - raise Exception('Invalid nu value, expected nonnegative integer.') - - @np.setter - def np(self, np): - if isinstance(np, int) and np > -1: - self.__np = np - else: - raise Exception('Invalid np value, expected nonnegative integer.') - - @ny_0.setter - def ny_0(self, ny_0): - if isinstance(ny_0, int) and ny_0 > -1: - self.__ny_0 = ny_0 - else: - raise Exception('Invalid ny_0 value, expected nonnegative integer.') - - @ny.setter - def ny(self, ny): - if isinstance(ny, int) and ny > -1: - self.__ny = ny - else: - raise Exception('Invalid ny value, expected nonnegative integer.') - - @ny_e.setter - def ny_e(self, ny_e): - if isinstance(ny_e, int) and ny_e > -1: - self.__ny_e = ny_e - else: - raise Exception('Invalid ny_e value, expected nonnegative integer.') - - @nr.setter - def nr(self, nr): - if isinstance(nr, int) and nr > -1: - self.__nr = nr - else: - raise Exception('Invalid nr value, expected nonnegative integer.') - - @nr_e.setter - def nr_e(self, nr_e): - if isinstance(nr_e, int) and nr_e > -1: - self.__nr_e = nr_e - else: - raise Exception('Invalid nr_e value, expected nonnegative integer.') - - @nh.setter - def nh(self, nh): - if isinstance(nh, int) and nh > -1: - self.__nh = nh - else: - raise Exception('Invalid nh value, expected nonnegative integer.') - - @nh_e.setter - def nh_e(self, nh_e): - if isinstance(nh_e, int) and nh_e > -1: - self.__nh_e = nh_e - else: - raise Exception('Invalid nh_e value, expected nonnegative integer.') - - @nphi.setter - def nphi(self, nphi): - if isinstance(nphi, int) and nphi > -1: - self.__nphi = nphi - else: - raise Exception('Invalid nphi value, expected nonnegative integer.') - - @nphi_e.setter - def nphi_e(self, nphi_e): - if isinstance(nphi_e, int) and nphi_e > -1: - self.__nphi_e = nphi_e - else: - raise Exception('Invalid nphi_e value, expected nonnegative integer.') - - @nbx.setter - def nbx(self, nbx): - if isinstance(nbx, int) and nbx > -1: - self.__nbx = nbx - else: - raise Exception('Invalid nbx value, expected nonnegative integer.') - - @nbxe_0.setter - def nbxe_0(self, nbxe_0): - if isinstance(nbxe_0, int) and nbxe_0 > -1: - self.__nbxe_0 = nbxe_0 - else: - raise Exception('Invalid nbxe_0 value, expected nonnegative integer.') - - @nbx_0.setter - def nbx_0(self, nbx_0): - if isinstance(nbx_0, int) and nbx_0 > -1: - self.__nbx_0 = nbx_0 - else: - raise Exception('Invalid nbx_0 value, expected nonnegative integer.') - - @nbx_e.setter - def nbx_e(self, nbx_e): - if isinstance(nbx_e, int) and nbx_e > -1: - self.__nbx_e = nbx_e - else: - raise Exception('Invalid nbx_e value, expected nonnegative integer.') - - @nbu.setter - def nbu(self, nbu): - if isinstance(nbu, int) and nbu > -1: - self.__nbu = nbu - else: - raise Exception('Invalid nbu value, expected nonnegative integer.') - - @nsbx.setter - def nsbx(self, nsbx): - if isinstance(nsbx, int) and nsbx > -1: - self.__nsbx = nsbx - else: - raise Exception('Invalid nsbx value, expected nonnegative integer.') - - @nsbx_e.setter - def nsbx_e(self, nsbx_e): - if isinstance(nsbx_e, int) and nsbx_e > -1: - self.__nsbx_e = nsbx_e - else: - raise Exception('Invalid nsbx_e value, expected nonnegative integer.') - - @nsbu.setter - def nsbu(self, nsbu): - if isinstance(nsbu, int) and nsbu > -1: - self.__nsbu = nsbu - else: - raise Exception('Invalid nsbu value, expected nonnegative integer.') - - @nsg.setter - def nsg(self, nsg): - if isinstance(nsg, int) and nsg > -1: - self.__nsg = nsg - else: - raise Exception('Invalid nsg value, expected nonnegative integer.') - - @nsg_e.setter - def nsg_e(self, nsg_e): - if isinstance(nsg_e, int) and nsg_e > -1: - self.__nsg_e = nsg_e - else: - raise Exception('Invalid nsg_e value, expected nonnegative integer.') - - @nsh.setter - def nsh(self, nsh): - if isinstance(nsh, int) and nsh > -1: - self.__nsh = nsh - else: - raise Exception('Invalid nsh value, expected nonnegative integer.') - - @nsh_e.setter - def nsh_e(self, nsh_e): - if isinstance(nsh_e, int) and nsh_e > -1: - self.__nsh_e = nsh_e - else: - raise Exception('Invalid nsh_e value, expected nonnegative integer.') - - @nsphi.setter - def nsphi(self, nsphi): - if isinstance(nsphi, int) and nsphi > -1: - self.__nsphi = nsphi - else: - raise Exception('Invalid nsphi value, expected nonnegative integer.') - - @nsphi_e.setter - def nsphi_e(self, nsphi_e): - if isinstance(nsphi_e, int) and nsphi_e > -1: - self.__nsphi_e = nsphi_e - else: - raise Exception('Invalid nsphi_e value, expected nonnegative integer.') - - @ns.setter - def ns(self, ns): - if isinstance(ns, int) and ns > -1: - self.__ns = ns - else: - raise Exception('Invalid ns value, expected nonnegative integer.') - - @ns_e.setter - def ns_e(self, ns_e): - if isinstance(ns_e, int) and ns_e > -1: - self.__ns_e = ns_e - else: - raise Exception('Invalid ns_e value, expected nonnegative integer.') - - @ng.setter - def ng(self, ng): - if isinstance(ng, int) and ng > -1: - self.__ng = ng - else: - raise Exception('Invalid ng value, expected nonnegative integer.') - - @ng_e.setter - def ng_e(self, ng_e): - if isinstance(ng_e, int) and ng_e > -1: - self.__ng_e = ng_e - else: - raise Exception('Invalid ng_e value, expected nonnegative integer.') - - @N.setter - def N(self, N): - if isinstance(N, int) and N > 0: - self.__N = N - else: - raise Exception('Invalid N value, expected positive integer.') - - def set(self, attr, value): - setattr(self, attr, value) - - -class AcadosOcpCost: - """ - Class containing the numerical data of the cost: - - NOTE: all cost terms, except for the terminal one are weighted with the corresponding time step. - This means given the time steps are :math:`\Delta t_0,..., \Delta t_N`, the total cost is given by: - :math:`c_\\text{total} = \Delta t_0 \cdot c_0(x_0, u_0, p_0, z_0) + ... + \Delta t_{N-1} \cdot c_{N-1}(x_0, u_0, p_0, z_0) + c_N(x_N, p_N)`. - - This means the Lagrange cost term is given in continuous time, this makes up for a seeminglessly OCP discretization with a nonuniform time grid. - - In case of LINEAR_LS: - stage cost is - :math:`l(x,u,z) = || V_x \, x + V_u \, u + V_z \, z - y_\\text{ref}||^2_W`, - terminal cost is - :math:`m(x) = || V^e_x \, x - y_\\text{ref}^e||^2_{W^e}` - - In case of NONLINEAR_LS: - stage cost is - :math:`l(x,u,z,p) = || y(x,u,z,p) - y_\\text{ref}||^2_W`, - terminal cost is - :math:`m(x,p) = || y^e(x,p) - y_\\text{ref}^e||^2_{W^e}` - - In case of CONVEX_OVER_NONLINEAR: - stage cost is - :math:`l(x,u,p) = \psi(y(x,u,p) - y_\\text{ref}, p)`, - terminal cost is - :math:`m(x, p) = \psi^e (y^e(x,p) - y_\\text{ref}^e, p)` - """ - def __init__(self): - # initial stage - self.__cost_type_0 = None - self.__W_0 = None - self.__Vx_0 = None - self.__Vu_0 = None - self.__Vz_0 = None - self.__yref_0 = None - self.__cost_ext_fun_type_0 = 'casadi' - # Lagrange term - self.__cost_type = 'LINEAR_LS' # cost type - self.__W = np.zeros((0,0)) - self.__Vx = np.zeros((0,0)) - self.__Vu = np.zeros((0,0)) - self.__Vz = np.zeros((0,0)) - self.__yref = np.array([]) - self.__Zl = np.array([]) - self.__Zu = np.array([]) - self.__zl = np.array([]) - self.__zu = np.array([]) - self.__cost_ext_fun_type = 'casadi' - # Mayer term - self.__cost_type_e = 'LINEAR_LS' - self.__W_e = np.zeros((0,0)) - self.__Vx_e = np.zeros((0,0)) - self.__yref_e = np.array([]) - self.__Zl_e = np.array([]) - self.__Zu_e = np.array([]) - self.__zl_e = np.array([]) - self.__zu_e = np.array([]) - self.__cost_ext_fun_type_e = 'casadi' - - # initial stage - @property - def cost_type_0(self): - """Cost type at initial shooting node (0) - -- string in {EXTERNAL, LINEAR_LS, NONLINEAR_LS, CONVEX_OVER_NONLINEAR} or :code:`None`. - Default: :code:`None`. - - .. note:: Cost at initial stage is the same as for intermediate shooting nodes if not set differently explicitly. - - .. note:: If :py:attr:`cost_type_0` is set to :code:`None` values in :py:attr:`W_0`, :py:attr:`Vx_0`, :py:attr:`Vu_0`, :py:attr:`Vz_0` and :py:attr:`yref_0` are ignored (set to :code:`None`). - """ - return self.__cost_type_0 - - @property - def W_0(self): - """:math:`W_0` - weight matrix at initial shooting node (0). - Default: :code:`None`. - """ - return self.__W_0 - - @property - def Vx_0(self): - """:math:`V_x^0` - x matrix coefficient at initial shooting node (0). - Default: :code:`None`. - """ - return self.__Vx_0 - - @property - def Vu_0(self): - """:math:`V_u^0` - u matrix coefficient at initial shooting node (0). - Default: :code:`None`. - """ - return self.__Vu_0 - - @property - def Vz_0(self): - """:math:`V_z^0` - z matrix coefficient at initial shooting node (0). - Default: :code:`None`. - """ - return self.__Vz_0 - - @property - def yref_0(self): - """:math:`y_\\text{ref}^0` - reference at initial shooting node (0). - Default: :code:`None`. - """ - return self.__yref_0 - - @property - def cost_ext_fun_type_0(self): - """Type of external function for cost at initial shooting node (0) - -- string in {casadi, generic} or :code:`None` - Default: :code:'casadi'. - - .. note:: Cost at initial stage is the same as for intermediate shooting nodes if not set differently explicitly. - """ - return self.__cost_ext_fun_type_0 - - @yref_0.setter - def yref_0(self, yref_0): - if isinstance(yref_0, np.ndarray) and len(yref_0.shape) == 1: - self.__yref_0 = yref_0 - else: - raise Exception('Invalid yref_0 value, expected 1-dimensional numpy array.') - - @W_0.setter - def W_0(self, W_0): - if isinstance(W_0, np.ndarray) and len(W_0.shape) == 2: - self.__W_0 = W_0 - else: - raise Exception('Invalid cost W_0 value. ' \ - + 'Should be 2 dimensional numpy array.') - - @Vx_0.setter - def Vx_0(self, Vx_0): - if isinstance(Vx_0, np.ndarray) and len(Vx_0.shape) == 2: - self.__Vx_0 = Vx_0 - else: - raise Exception('Invalid cost Vx_0 value. ' \ - + 'Should be 2 dimensional numpy array.') - - @Vu_0.setter - def Vu_0(self, Vu_0): - if isinstance(Vu_0, np.ndarray) and len(Vu_0.shape) == 2: - self.__Vu_0 = Vu_0 - else: - raise Exception('Invalid cost Vu_0 value. ' \ - + 'Should be 2 dimensional numpy array.') - - @Vz_0.setter - def Vz_0(self, Vz_0): - if isinstance(Vz_0, np.ndarray) and len(Vz_0.shape) == 2: - self.__Vz_0 = Vz_0 - else: - raise Exception('Invalid cost Vz_0 value. ' \ - + 'Should be 2 dimensional numpy array.') - - @cost_ext_fun_type_0.setter - def cost_ext_fun_type_0(self, cost_ext_fun_type_0): - if cost_ext_fun_type_0 in ['casadi', 'generic']: - self.__cost_ext_fun_type_0 = cost_ext_fun_type_0 - else: - raise Exception('Invalid cost_ext_fun_type_0 value, expected numpy array.') - - # Lagrange term - @property - def cost_type(self): - """ - Cost type at intermediate shooting nodes (1 to N-1) - -- string in {EXTERNAL, LINEAR_LS, NONLINEAR_LS, CONVEX_OVER_NONLINEAR}. - Default: 'LINEAR_LS'. - """ - return self.__cost_type - - @property - def W(self): - """:math:`W` - weight matrix at intermediate shooting nodes (1 to N-1). - Default: :code:`np.zeros((0,0))`. - """ - return self.__W - - @property - def Vx(self): - """:math:`V_x` - x matrix coefficient at intermediate shooting nodes (1 to N-1). - Default: :code:`np.zeros((0,0))`. - """ - return self.__Vx - - @property - def Vu(self): - """:math:`V_u` - u matrix coefficient at intermediate shooting nodes (1 to N-1). - Default: :code:`np.zeros((0,0))`. - """ - return self.__Vu - - @property - def Vz(self): - """:math:`V_z` - z matrix coefficient at intermediate shooting nodes (1 to N-1). - Default: :code:`np.zeros((0,0))`. - """ - return self.__Vz - - @property - def yref(self): - """:math:`y_\\text{ref}` - reference at intermediate shooting nodes (1 to N-1). - Default: :code:`np.array([])`. - """ - return self.__yref - - @property - def Zl(self): - """:math:`Z_l` - diagonal of Hessian wrt lower slack at intermediate shooting nodes (0 to N-1). - Default: :code:`np.array([])`. - """ - return self.__Zl - - @property - def Zu(self): - """:math:`Z_u` - diagonal of Hessian wrt upper slack at intermediate shooting nodes (0 to N-1). - Default: :code:`np.array([])`. - """ - return self.__Zu - - @property - def zl(self): - """:math:`z_l` - gradient wrt lower slack at intermediate shooting nodes (0 to N-1). - Default: :code:`np.array([])`. - """ - return self.__zl - - @property - def zu(self): - """:math:`z_u` - gradient wrt upper slack at intermediate shooting nodes (0 to N-1). - Default: :code:`np.array([])`. - """ - return self.__zu - - @property - def cost_ext_fun_type(self): - """Type of external function for cost at intermediate shooting nodes (1 to N-1). - -- string in {casadi, generic} - Default: :code:'casadi'. - """ - return self.__cost_ext_fun_type - - @cost_type.setter - def cost_type(self, cost_type): - cost_types = ('LINEAR_LS', 'NONLINEAR_LS', 'EXTERNAL', 'CONVEX_OVER_NONLINEAR') - if cost_type in cost_types: - self.__cost_type = cost_type - else: - raise Exception('Invalid cost_type value.') - - @cost_type_0.setter - def cost_type_0(self, cost_type_0): - cost_types = ('LINEAR_LS', 'NONLINEAR_LS', 'EXTERNAL', 'CONVEX_OVER_NONLINEAR') - if cost_type_0 in cost_types: - self.__cost_type_0 = cost_type_0 - else: - raise Exception('Invalid cost_type_0 value.') - - @W.setter - def W(self, W): - if isinstance(W, np.ndarray) and len(W.shape) == 2: - self.__W = W - else: - raise Exception('Invalid cost W value. ' \ - + 'Should be 2 dimensional numpy array.') - - - @Vx.setter - def Vx(self, Vx): - if isinstance(Vx, np.ndarray) and len(Vx.shape) == 2: - self.__Vx = Vx - else: - raise Exception('Invalid cost Vx value. ' \ - + 'Should be 2 dimensional numpy array.') - - @Vu.setter - def Vu(self, Vu): - if isinstance(Vu, np.ndarray) and len(Vu.shape) == 2: - self.__Vu = Vu - else: - raise Exception('Invalid cost Vu value. ' \ - + 'Should be 2 dimensional numpy array.') - - @Vz.setter - def Vz(self, Vz): - if isinstance(Vz, np.ndarray) and len(Vz.shape) == 2: - self.__Vz = Vz - else: - raise Exception('Invalid cost Vz value. ' \ - + 'Should be 2 dimensional numpy array.') - - @yref.setter - def yref(self, yref): - if isinstance(yref, np.ndarray) and len(yref.shape) == 1: - self.__yref = yref - else: - raise Exception('Invalid yref value, expected 1-dimensional numpy array.') - - @Zl.setter - def Zl(self, Zl): - if isinstance(Zl, np.ndarray): - self.__Zl = Zl - else: - raise Exception('Invalid Zl value, expected numpy array.') - - @Zu.setter - def Zu(self, Zu): - if isinstance(Zu, np.ndarray): - self.__Zu = Zu - else: - raise Exception('Invalid Zu value, expected numpy array.') - - @zl.setter - def zl(self, zl): - if isinstance(zl, np.ndarray): - self.__zl = zl - else: - raise Exception('Invalid zl value, expected numpy array.') - - @zu.setter - def zu(self, zu): - if isinstance(zu, np.ndarray): - self.__zu = zu - else: - raise Exception('Invalid zu value, expected numpy array.') - - @cost_ext_fun_type.setter - def cost_ext_fun_type(self, cost_ext_fun_type): - if cost_ext_fun_type in ['casadi', 'generic']: - self.__cost_ext_fun_type = cost_ext_fun_type - else: - raise Exception("Invalid cost_ext_fun_type value, expected one in ['casadi', 'generic'].") - - # Mayer term - @property - def cost_type_e(self): - """ - Cost type at terminal shooting node (N) - -- string in {EXTERNAL, LINEAR_LS, NONLINEAR_LS, CONVEX_OVER_NONLINEAR}. - Default: 'LINEAR_LS'. - """ - return self.__cost_type_e - - @property - def W_e(self): - """:math:`W_e` - weight matrix at terminal shooting node (N). - Default: :code:`np.zeros((0,0))`. - """ - return self.__W_e - - @property - def Vx_e(self): - """:math:`V_x^e` - x matrix coefficient for cost at terminal shooting node (N). - Default: :code:`np.zeros((0,0))`. - """ - return self.__Vx_e - - @property - def yref_e(self): - """:math:`y_\\text{ref}^e` - cost reference at terminal shooting node (N). - Default: :code:`np.array([])`. - """ - return self.__yref_e - - @property - def Zl_e(self): - """:math:`Z_l^e` - diagonal of Hessian wrt lower slack at terminal shooting node (N). - Default: :code:`np.array([])`. - """ - return self.__Zl_e - - @property - def Zu_e(self): - """:math:`Z_u^e` - diagonal of Hessian wrt upper slack at terminal shooting node (N). - Default: :code:`np.array([])`. - """ - return self.__Zu_e - - @property - def zl_e(self): - """:math:`z_l^e` - gradient wrt lower slack at terminal shooting node (N). - Default: :code:`np.array([])`. - """ - return self.__zl_e - - @property - def zu_e(self): - """:math:`z_u^e` - gradient wrt upper slack at terminal shooting node (N). - Default: :code:`np.array([])`. - """ - return self.__zu_e - - @property - def cost_ext_fun_type_e(self): - """Type of external function for cost at terminal shooting node (N). - -- string in {casadi, generic} - Default: :code:'casadi'. - """ - return self.__cost_ext_fun_type_e - - @cost_type_e.setter - def cost_type_e(self, cost_type_e): - cost_types = ('LINEAR_LS', 'NONLINEAR_LS', 'EXTERNAL', 'CONVEX_OVER_NONLINEAR') - - if cost_type_e in cost_types: - self.__cost_type_e = cost_type_e - else: - raise Exception('Invalid cost_type_e value.') - - @W_e.setter - def W_e(self, W_e): - if isinstance(W_e, np.ndarray) and len(W_e.shape) == 2: - self.__W_e = W_e - else: - raise Exception('Invalid cost W_e value. ' \ - + 'Should be 2 dimensional numpy array.') - - @Vx_e.setter - def Vx_e(self, Vx_e): - if isinstance(Vx_e, np.ndarray) and len(Vx_e.shape) == 2: - self.__Vx_e = Vx_e - else: - raise Exception('Invalid cost Vx_e value. ' \ - + 'Should be 2 dimensional numpy array.') - - @yref_e.setter - def yref_e(self, yref_e): - if isinstance(yref_e, np.ndarray) and len(yref_e.shape) == 1: - self.__yref_e = yref_e - else: - raise Exception('Invalid yref_e value, expected 1-dimensional numpy array.') - - @Zl_e.setter - def Zl_e(self, Zl_e): - if isinstance(Zl_e, np.ndarray): - self.__Zl_e = Zl_e - else: - raise Exception('Invalid Zl_e value, expected numpy array.') - - @Zu_e.setter - def Zu_e(self, Zu_e): - if isinstance(Zu_e, np.ndarray): - self.__Zu_e = Zu_e - else: - raise Exception('Invalid Zu_e value, expected numpy array.') - - @zl_e.setter - def zl_e(self, zl_e): - if isinstance(zl_e, np.ndarray): - self.__zl_e = zl_e - else: - raise Exception('Invalid zl_e value, expected numpy array.') - - @zu_e.setter - def zu_e(self, zu_e): - if isinstance(zu_e, np.ndarray): - self.__zu_e = zu_e - else: - raise Exception('Invalid zu_e value, expected numpy array.') - - @cost_ext_fun_type_e.setter - def cost_ext_fun_type_e(self, cost_ext_fun_type_e): - if cost_ext_fun_type_e in ['casadi', 'generic']: - self.__cost_ext_fun_type_e = cost_ext_fun_type_e - else: - raise Exception("Invalid cost_ext_fun_type_e value, expected one in ['casadi', 'generic'].") - - def set(self, attr, value): - setattr(self, attr, value) - - -def print_J_to_idx_note(): - print("NOTE: J* matrix is converted to zero based vector idx* vector, which is returned here.") - - -class AcadosOcpConstraints: - """ - class containing the description of the constraints - """ - def __init__(self): - self.__constr_type = 'BGH' - self.__constr_type_e = 'BGH' - # initial x - self.__lbx_0 = np.array([]) - self.__ubx_0 = np.array([]) - self.__idxbx_0 = np.array([]) - self.__idxbxe_0 = np.array([]) - # state bounds - self.__lbx = np.array([]) - self.__ubx = np.array([]) - self.__idxbx = np.array([]) - # bounds on x at shooting node N - self.__lbx_e = np.array([]) - self.__ubx_e = np.array([]) - self.__idxbx_e = np.array([]) - # bounds on u - self.__lbu = np.array([]) - self.__ubu = np.array([]) - self.__idxbu = np.array([]) - # polytopic constraints - self.__lg = np.array([]) - self.__ug = np.array([]) - self.__D = np.zeros((0,0)) - self.__C = np.zeros((0,0)) - # polytopic constraints at shooting node N - self.__C_e = np.zeros((0,0)) - self.__lg_e = np.array([]) - self.__ug_e = np.array([]) - # nonlinear constraints - self.__lh = np.array([]) - self.__uh = np.array([]) - # nonlinear constraints at shooting node N - self.__uh_e = np.array([]) - self.__lh_e = np.array([]) - # convex-over-nonlinear constraints - self.__lphi = np.array([]) - self.__uphi = np.array([]) - # nonlinear constraints at shooting node N - self.__uphi_e = np.array([]) - self.__lphi_e = np.array([]) - # SLACK BOUNDS - # soft bounds on x - self.__lsbx = np.array([]) - self.__usbx = np.array([]) - self.__idxsbx = np.array([]) - # soft bounds on u - self.__lsbu = np.array([]) - self.__usbu = np.array([]) - self.__idxsbu = np.array([]) - # soft bounds on x at shooting node N - self.__lsbx_e = np.array([]) - self.__usbx_e = np.array([]) - self.__idxsbx_e= np.array([]) - # soft bounds on general linear constraints - self.__lsg = np.array([]) - self.__usg = np.array([]) - self.__idxsg = np.array([]) - # soft bounds on nonlinear constraints - self.__lsh = np.array([]) - self.__ush = np.array([]) - self.__idxsh = np.array([]) - # soft bounds on nonlinear constraints - self.__lsphi = np.array([]) - self.__usphi = np.array([]) - self.__idxsphi = np.array([]) - # soft bounds on general linear constraints at shooting node N - self.__lsg_e = np.array([]) - self.__usg_e = np.array([]) - self.__idxsg_e = np.array([]) - # soft bounds on nonlinear constraints at shooting node N - self.__lsh_e = np.array([]) - self.__ush_e = np.array([]) - self.__idxsh_e = np.array([]) - # soft bounds on nonlinear constraints at shooting node N - self.__lsphi_e = np.array([]) - self.__usphi_e = np.array([]) - self.__idxsphi_e = np.array([]) - - - # types - @property - def constr_type(self): - """Constraints type for shooting nodes (0 to N-1). string in {BGH, BGP}. - Default: BGH; BGP is for convex over nonlinear.""" - return self.__constr_type - - @property - def constr_type_e(self): - """Constraints type for terminal shooting node N. string in {BGH, BGP}. - Default: BGH; BGP is for convex over nonlinear.""" - return self.__constr_type_e - - # initial bounds on x - @property - def lbx_0(self): - """:math:`\\underline{x_0}` - lower bounds on x at initial stage 0. - Type: :code:`np.ndarray`; default: :code:`np.array([])`.""" - return self.__lbx_0 - - @property - def ubx_0(self): - """:math:`\\bar{x_0}` - upper bounds on x at initial stage 0. - Type: :code:`np.ndarray`; default: :code:`np.array([])`""" - return self.__ubx_0 - - @property - def Jbx_0(self): - """:math:`J_{bx,0}` - matrix coefficient for bounds on x at initial stage 0. - Translated internally to :py:attr:`idxbx_0`""" - print_J_to_idx_note() - return self.__idxbx_0 - - @property - def idxbx_0(self): - """Indices of bounds on x at initial stage 0 - -- can be set automatically via x0. - Can be set by using :py:attr:`Jbx_0`. - Type: :code:`np.ndarray`; default: :code:`np.array([])`""" - return self.__idxbx_0 - - @property - def idxbxe_0(self): - """Indices of bounds on x0 that are equalities -- can be set automatically via :py:attr:`x0`. - Type: :code:`np.ndarray`; default: :code:`np.array([])`""" - return self.__idxbxe_0 - - # bounds on x - @property - def lbx(self): - """:math:`\\underline{x}` - lower bounds on x at intermediate shooting nodes (1 to N-1). - Type: :code:`np.ndarray`; default: :code:`np.array([])`""" - return self.__lbx - - @property - def ubx(self): - """:math:`\\bar{x}` - upper bounds on x at intermediate shooting nodes (1 to N-1). - Type: :code:`np.ndarray`; default: :code:`np.array([])`""" - return self.__ubx - - @property - def idxbx(self): - """indices of bounds on x (defines :math:`J_{bx}`) at intermediate shooting nodes (1 to N-1). - Can be set by using :py:attr:`Jbx`. - Type: :code:`np.ndarray`; default: :code:`np.array([])`""" - return self.__idxbx - - @property - def Jbx(self): - """:math:`J_{bx}` - matrix coefficient for bounds on x - at intermediate shooting nodes (1 to N-1). - Translated internally into :py:attr:`idxbx`.""" - print_J_to_idx_note() - return self.__idxbx - - # bounds on x at shooting node N - @property - def lbx_e(self): - """:math:`\\underline{x}^e` - lower bounds on x at terminal shooting node N. - Type: :code:`np.ndarray`; default: :code:`np.array([])`""" - return self.__lbx_e - - @property - def ubx_e(self): - """:math:`\\bar{x}^e` - upper bounds on x at terminal shooting node N. - Type: :code:`np.ndarray`; default: :code:`np.array([])`""" - return self.__ubx_e - - @property - def idxbx_e(self): - """Indices for bounds on x at terminal shooting node N (defines :math:`J_{bx}^e`). - Can be set by using :py:attr:`Jbx_e`. - Type: :code:`np.ndarray`; default: :code:`np.array([])`""" - return self.__idxbx_e - - @property - def Jbx_e(self): - """:math:`J_{bx}^e` matrix coefficient for bounds on x at terminal shooting node N. - Translated internally into :py:attr:`idxbx_e`.""" - print_J_to_idx_note() - return self.__idxbx_e - - # bounds on u - @property - def lbu(self): - """:math:`\\underline{u}` - lower bounds on u at shooting nodes (0 to N-1). - Type: :code:`np.ndarray`; default: :code:`np.array([])` - """ - return self.__lbu - - @property - def ubu(self): - """:math:`\\bar{u}` - upper bounds on u at shooting nodes (0 to N-1). - Type: :code:`np.ndarray`; default: :code:`np.array([])` - """ - return self.__ubu - - @property - def idxbu(self): - """Indices of bounds on u (defines :math:`J_{bu}`) at shooting nodes (0 to N-1). - Can be set by using :py:attr:`Jbu`. - Type: :code:`np.ndarray`; default: :code:`np.array([])` - """ - return self.__idxbu - - @property - def Jbu(self): - """:math:`J_{bu}` - matrix coefficient for bounds on u at shooting nodes (0 to N-1). - Translated internally to :py:attr:`idxbu`. - """ - print_J_to_idx_note() - return self.__idxbu - - # polytopic constraints - @property - def C(self): - """:math:`C` - C matrix in :math:`\\underline{g} \\leq D \, u + C \, x \\leq \\bar{g}` - at shooting nodes (0 to N-1). - Type: :code:`np.ndarray`; default: :code:`np.array((0,0))`. - """ - return self.__C - - @property - def D(self): - """:math:`D` - D matrix in :math:`\\underline{g} \\leq D \, u + C \, x \\leq \\bar{g}` - at shooting nodes (0 to N-1). - Type: :code:`np.ndarray`; default: :code:`np.array((0,0))` - """ - return self.__D - - @property - def lg(self): - """:math:`\\underline{g}` - lower bound for general polytopic inequalities - at shooting nodes (0 to N-1). - Type: :code:`np.ndarray`; default: :code:`np.array([])` - """ - return self.__lg - - @property - def ug(self): - """:math:`\\bar{g}` - upper bound for general polytopic inequalities - at shooting nodes (0 to N-1). - Type: :code:`np.ndarray`; default: :code:`np.array([])`. - """ - return self.__ug - - # polytopic constraints at shooting node N - @property - def C_e(self): - """:math:`C^e` - C matrix at terminal shooting node N. - Type: :code:`np.ndarray`; default: :code:`np.array((0,0))`. - """ - return self.__C_e - - @property - def lg_e(self): - """:math:`\\underline{g}^e` - lower bound on general polytopic inequalities - at terminal shooting node N. - Type: :code:`np.ndarray`; default: :code:`np.array([])`. - """ - return self.__lg_e - - @property - def ug_e(self): - """:math:`\\bar{g}^e` - upper bound on general polytopic inequalities - at terminal shooting node N. - Type: :code:`np.ndarray`; default: :code:`np.array([])`. - """ - return self.__ug_e - - - # nonlinear constraints - @property - def lh(self): - """:math:`\\underline{h}` - lower bound for nonlinear inequalities - at shooting nodes (0 to N-1). - Type: :code:`np.ndarray`; default: :code:`np.array([])`. - """ - return self.__lh - - @property - def uh(self): - """:math:`\\bar{h}` - upper bound for nonlinear inequalities - at shooting nodes (0 to N-1). - Type: :code:`np.ndarray`; default: :code:`np.array([])`. - """ - return self.__uh - - # nonlinear constraints at shooting node N - @property - def lh_e(self): - """:math:`\\underline{h}^e` - lower bound on nonlinear inequalities - at terminal shooting node N. - Type: :code:`np.ndarray`; default: :code:`np.array([])`. - """ - return self.__lh_e - - @property - def uh_e(self): - """:math:`\\bar{h}^e` - upper bound on nonlinear inequalities - at terminal shooting node N. - Type: :code:`np.ndarray`; default: :code:`np.array([])`. - """ - return self.__uh_e - - # convex-over-nonlinear constraints - @property - def lphi(self): - """:math:`\\underline{\phi}` - lower bound for convex-over-nonlinear inequalities - at shooting nodes (0 to N-1). - Type: :code:`np.ndarray`; default: :code:`np.array([])`. - """ - return self.__lphi - - @property - def uphi(self): - """:math:`\\bar{\phi}` - upper bound for convex-over-nonlinear inequalities - at shooting nodes (0 to N-1). - Type: :code:`np.ndarray`; default: :code:`np.array([])`. - """ - return self.__uphi - - # convex-over-nonlinear constraints at shooting node N - @property - def lphi_e(self): - """:math:`\\underline{\phi}^e` - lower bound on convex-over-nonlinear inequalities - at terminal shooting node N. - Type: :code:`np.ndarray`; default: :code:`np.array([])`. - """ - return self.__lphi_e - - @property - def uphi_e(self): - """:math:`\\bar{\phi}^e` - upper bound on convex-over-nonlinear inequalities - at terminal shooting node N. - Type: :code:`np.ndarray`; default: :code:`np.array([])`. - """ - return self.__uphi_e - - - # SLACK bounds - # soft bounds on x - @property - def lsbx(self): - """Lower bounds on slacks corresponding to soft lower bounds on x - at stages (1 to N-1); - not required - zeros by default""" - return self.__lsbx - - @property - def usbx(self): - """Lower bounds on slacks corresponding to soft upper bounds on x - at stages (1 to N-1); - not required - zeros by default""" - return self.__usbx - - @property - def idxsbx(self): - """Indices of soft bounds on x within the indices of bounds on x - at stages (1 to N-1). - Can be set by using :py:attr:`Jsbx`. - Type: :code:`np.ndarray`; default: :code:`np.array([])`""" - return self.__idxsbx - - @property - def Jsbx(self): - """:math:`J_{sbx}` - matrix coefficient for soft bounds on x - at stages (1 to N-1); - Translated internally into :py:attr:`idxsbx`.""" - print_J_to_idx_note() - return self.__idxsbx - - # soft bounds on u - @property - def lsbu(self): - """Lower bounds on slacks corresponding to soft lower bounds on u - at stages (0 to N-1). - Not required - zeros by default.""" - return self.__lsbu - - @property - def usbu(self): - """Lower bounds on slacks corresponding to soft upper bounds on u - at stages (0 to N-1); - not required - zeros by default""" - return self.__usbu - - @property - def idxsbu(self): - """Indices of soft bounds on u within the indices of bounds on u - at stages (0 to N-1). - Can be set by using :py:attr:`Jsbu`. - Type: :code:`np.ndarray`; default: :code:`np.array([])`""" - return self.__idxsbu - - @property - def Jsbu(self): - """:math:`J_{sbu}` - matrix coefficient for soft bounds on u - at stages (0 to N-1); - internally translated into :py:attr:`idxsbu`""" - print_J_to_idx_note() - return self.__idxsbu - - # soft bounds on x at shooting node N - @property - def lsbx_e(self): - """Lower bounds on slacks corresponding to soft lower bounds on x at shooting node N. - Not required - zeros by default""" - return self.__lsbx_e - - @property - def usbx_e(self): - """Lower bounds on slacks corresponding to soft upper bounds on x at shooting node N. - Not required - zeros by default""" - return self.__usbx_e - - @property - def idxsbx_e(self): - """Indices of soft bounds on x at shooting node N, within the indices of bounds on x at terminal shooting node N. - Can be set by using :py:attr:`Jsbx_e`. - Type: :code:`np.ndarray`; default: :code:`np.array([])`""" - return self.__idxsbx_e - - @property - def Jsbx_e(self): - """:math:`J_{sbx}^e` - matrix coefficient for soft bounds on x at terminal shooting node N. - Translated internally to :py:attr:`idxsbx_e`""" - print_J_to_idx_note() - return self.__idxsbx_e - - # soft general linear constraints - @property - def lsg(self): - """Lower bounds on slacks corresponding to soft lower bounds for general linear constraints - at stages (0 to N-1). - Type: :code:`np.ndarray`; default: :code:`np.array([])` - """ - return self.__lsg - - @property - def usg(self): - """Lower bounds on slacks corresponding to soft upper bounds for general linear constraints. - Not required - zeros by default""" - return self.__usg - - @property - def idxsg(self): - """Indices of soft general linear constraints within the indices of general linear constraints. - Can be set by using :py:attr:`Jsg`. - Type: :code:`np.ndarray`; default: :code:`np.array([])`""" - return self.__idxsg - - @property - def Jsg(self): - """:math:`J_{sg}` - matrix coefficient for soft bounds on general linear constraints. - Translated internally to :py:attr:`idxsg`""" - print_J_to_idx_note() - return self.__idxsg - - # soft nonlinear constraints - @property - def lsh(self): - """Lower bounds on slacks corresponding to soft lower bounds for nonlinear constraints. - Not required - zeros by default""" - return self.__lsh - - @property - def ush(self): - """Lower bounds on slacks corresponding to soft upper bounds for nonlinear constraints. - Not required - zeros by default""" - return self.__ush - - @property - def idxsh(self): - """Indices of soft nonlinear constraints within the indices of nonlinear constraints. - Can be set by using :py:attr:`Jbx`. - Type: :code:`np.ndarray`; default: :code:`np.array([])`""" - return self.__idxsh - - @property - def Jsh(self): - """:math:`J_{sh}` - matrix coefficient for soft bounds on nonlinear constraints. - Translated internally to :py:attr:`idxsh`""" - print_J_to_idx_note() - return self.__idxsh - - # soft bounds on convex-over-nonlinear constraints - @property - def lsphi(self): - """Lower bounds on slacks corresponding to soft lower bounds for convex-over-nonlinear constraints. - Not required - zeros by default""" - return self.__lsphi - - @property - def usphi(self): - """Lower bounds on slacks corresponding to soft upper bounds for convex-over-nonlinear constraints. - Not required - zeros by default""" - return self.__usphi - - @property - def idxsphi(self): - """Indices of soft convex-over-nonlinear constraints within the indices of nonlinear constraints. - Can be set by using :py:attr:`Jsphi`. - Type: :code:`np.ndarray`; default: :code:`np.array([])`""" - return self.__idxsphi - - @property - def Jsphi(self): - """:math:`J_{s, \phi}` - matrix coefficient for soft bounds on convex-over-nonlinear constraints. - Translated internally into :py:attr:`idxsphi`.""" - print_J_to_idx_note() - return self.__idxsphi - - - # soft bounds on general linear constraints at shooting node N - @property - def lsg_e(self): - """Lower bounds on slacks corresponding to soft lower bounds for general linear constraints at shooting node N. - Not required - zeros by default""" - return self.__lsg_e - - @property - def usg_e(self): - """Lower bounds on slacks corresponding to soft upper bounds for general linear constraints at shooting node N. - Not required - zeros by default""" - return self.__usg_e - - @property - def idxsg_e(self): - """Indices of soft general linear constraints at shooting node N within the indices of general linear constraints at shooting node N. - Can be set by using :py:attr:`Jsg_e`.""" - return self.__idxsg_e - - @property - def Jsg_e(self): - """:math:`J_{s,h}^e` - matrix coefficient for soft bounds on general linear constraints at terminal shooting node N. - Translated internally to :py:attr:`idxsg_e`""" - print_J_to_idx_note() - return self.__idxsg_e - - - # soft bounds on nonlinear constraints at shooting node N - @property - def lsh_e(self): - """Lower bounds on slacks corresponding to soft lower bounds for nonlinear constraints at terminal shooting node N. - Not required - zeros by default""" - return self.__lsh_e - - @property - def ush_e(self): - """Lower bounds on slacks corresponding to soft upper bounds for nonlinear constraints at terminal shooting node N. - Not required - zeros by default""" - return self.__ush_e - - @property - def idxsh_e(self): - """Indices of soft nonlinear constraints at shooting node N within the indices of nonlinear constraints at terminal shooting node N. - Can be set by using :py:attr:`Jsh_e`.""" - return self.__idxsh_e - - @property - def Jsh_e(self): - """:math:`J_{s,h}^e` - matrix coefficient for soft bounds on nonlinear constraints at terminal shooting node N; fills :py:attr:`idxsh_e`""" - print_J_to_idx_note() - return self.__idxsh_e - - # soft bounds on convex-over-nonlinear constraints at shooting node N - @property - def lsphi_e(self): - """Lower bounds on slacks corresponding to soft lower bounds for convex-over-nonlinear constraints at terminal shooting node N. - Not required - zeros by default""" - return self.__lsphi_e - - @property - def usphi_e(self): - """Lower bounds on slacks corresponding to soft upper bounds for convex-over-nonlinear constraints at terminal shooting node N. - Not required - zeros by default""" - return self.__usphi_e - - @property - def idxsphi_e(self): - """Indices of soft nonlinear constraints at shooting node N within the indices of nonlinear constraints at terminal shooting node N. - Can be set by using :py:attr:`Jsphi_e`. - Type: :code:`np.ndarray`; default: :code:`np.array([])`""" - return self.__idxsphi_e - - @property - def Jsphi_e(self): - """:math:`J_{sh}^e` - matrix coefficient for soft bounds on convex-over-nonlinear constraints at shooting node N. - Translated internally to :py:attr:`idxsphi_e`""" - print_J_to_idx_note() - return self.__idxsphi_e - - @property - def x0(self): - """:math:`x_0 \\in \mathbb{R}^{n_x}` - initial state -- - Translated internally to :py:attr:`idxbx_0`, :py:attr:`lbx_0`, :py:attr:`ubx_0`, :py:attr:`idxbxe_0` """ - print("x0 is converted to lbx_0, ubx_0, idxbx_0") - print("idxbx_0: ", self.__idxbx_0) - print("lbx_0: ", self.__lbx_0) - print("ubx_0: ", self.__ubx_0) - print("idxbxe_0: ", self.__idxbxe_0) - return None - - # SETTERS - @constr_type.setter - def constr_type(self, constr_type): - constr_types = ('BGH', 'BGP') - if constr_type in constr_types: - self.__constr_type = constr_type - else: - raise Exception('Invalid constr_type value. Possible values are:\n\n' \ - + ',\n'.join(constr_types) + '.\n\nYou have: ' + constr_type + '.\n\n') - - @constr_type_e.setter - def constr_type_e(self, constr_type_e): - constr_types = ('BGH', 'BGP') - if constr_type_e in constr_types: - self.__constr_type_e = constr_type_e - else: - raise Exception('Invalid constr_type_e value. Possible values are:\n\n' \ - + ',\n'.join(constr_types) + '.\n\nYou have: ' + constr_type_e + '.\n\n') - - # initial x - @lbx_0.setter - def lbx_0(self, lbx_0): - if isinstance(lbx_0, np.ndarray): - self.__lbx_0 = lbx_0 - else: - raise Exception('Invalid lbx_0 value.') - - @ubx_0.setter - def ubx_0(self, ubx_0): - if isinstance(ubx_0, np.ndarray): - self.__ubx_0 = ubx_0 - else: - raise Exception('Invalid ubx_0 value.') - - @idxbx_0.setter - def idxbx_0(self, idxbx_0): - if isinstance(idxbx_0, np.ndarray): - self.__idxbx_0 = idxbx_0 - else: - raise Exception('Invalid idxbx_0 value.') - - @Jbx_0.setter - def Jbx_0(self, Jbx_0): - if isinstance(Jbx_0, np.ndarray): - self.__idxbx_0 = J_to_idx(Jbx_0) - else: - raise Exception('Invalid Jbx_0 value.') - - @idxbxe_0.setter - def idxbxe_0(self, idxbxe_0): - if isinstance(idxbxe_0, np.ndarray): - self.__idxbxe_0 = idxbxe_0 - else: - raise Exception('Invalid idxbxe_0 value.') - - - @x0.setter - def x0(self, x0): - if isinstance(x0, np.ndarray): - self.__lbx_0 = x0 - self.__ubx_0 = x0 - self.__idxbx_0 = np.arange(x0.size) - self.__idxbxe_0 = np.arange(x0.size) - else: - raise Exception('Invalid x0 value.') - - # bounds on x - @lbx.setter - def lbx(self, lbx): - if isinstance(lbx, np.ndarray): - self.__lbx = lbx - else: - raise Exception('Invalid lbx value.') - - @ubx.setter - def ubx(self, ubx): - if isinstance(ubx, np.ndarray): - self.__ubx = ubx - else: - raise Exception('Invalid ubx value.') - - @idxbx.setter - def idxbx(self, idxbx): - if isinstance(idxbx, np.ndarray): - self.__idxbx = idxbx - else: - raise Exception('Invalid idxbx value.') - - @Jbx.setter - def Jbx(self, Jbx): - if isinstance(Jbx, np.ndarray): - self.__idxbx = J_to_idx(Jbx) - else: - raise Exception('Invalid Jbx value.') - - # bounds on u - @lbu.setter - def lbu(self, lbu): - if isinstance(lbu, np.ndarray): - self.__lbu = lbu - else: - raise Exception('Invalid lbu value.') - - @ubu.setter - def ubu(self, ubu): - if isinstance(ubu, np.ndarray): - self.__ubu = ubu - else: - raise Exception('Invalid ubu value.') - - @idxbu.setter - def idxbu(self, idxbu): - if isinstance(idxbu, np.ndarray): - self.__idxbu = idxbu - else: - raise Exception('Invalid idxbu value.') - - @Jbu.setter - def Jbu(self, Jbu): - if isinstance(Jbu, np.ndarray): - self.__idxbu = J_to_idx(Jbu) - else: - raise Exception('Invalid Jbu value.') - - # bounds on x at shooting node N - @lbx_e.setter - def lbx_e(self, lbx_e): - if isinstance(lbx_e, np.ndarray): - self.__lbx_e = lbx_e - else: - raise Exception('Invalid lbx_e value.') - - @ubx_e.setter - def ubx_e(self, ubx_e): - if isinstance(ubx_e, np.ndarray): - self.__ubx_e = ubx_e - else: - raise Exception('Invalid ubx_e value.') - - @idxbx_e.setter - def idxbx_e(self, idxbx_e): - if isinstance(idxbx_e, np.ndarray): - self.__idxbx_e = idxbx_e - else: - raise Exception('Invalid idxbx_e value.') - - @Jbx_e.setter - def Jbx_e(self, Jbx_e): - if isinstance(Jbx_e, np.ndarray): - self.__idxbx_e = J_to_idx(Jbx_e) - else: - raise Exception('Invalid Jbx_e value.') - - # polytopic constraints - @D.setter - def D(self, D): - if isinstance(D, np.ndarray) and len(D.shape) == 2: - self.__D = D - else: - raise Exception('Invalid constraint D value.' \ - + 'Should be 2 dimensional numpy array.') - - @C.setter - def C(self, C): - if isinstance(C, np.ndarray) and len(C.shape) == 2: - self.__C = C - else: - raise Exception('Invalid constraint C value.' \ - + 'Should be 2 dimensional numpy array.') - - @lg.setter - def lg(self, lg): - if isinstance(lg, np.ndarray): - self.__lg = lg - else: - raise Exception('Invalid lg value.') - - @ug.setter - def ug(self, ug): - if isinstance(ug, np.ndarray): - self.__ug = ug - else: - raise Exception('Invalid ug value.') - - # polytopic constraints at shooting node N - @C_e.setter - def C_e(self, C_e): - if isinstance(C_e, np.ndarray) and len(C_e.shape) == 2: - self.__C_e = C_e - else: - raise Exception('Invalid constraint C_e value.' \ - + 'Should be 2 dimensional numpy array.') - - @lg_e.setter - def lg_e(self, lg_e): - if isinstance(lg_e, np.ndarray): - self.__lg_e = lg_e - else: - raise Exception('Invalid lg_e value.') - - @ug_e.setter - def ug_e(self, ug_e): - if isinstance(ug_e, np.ndarray): - self.__ug_e = ug_e - else: - raise Exception('Invalid ug_e value.') - - # nonlinear constraints - @lh.setter - def lh(self, lh): - if isinstance(lh, np.ndarray): - self.__lh = lh - else: - raise Exception('Invalid lh value.') - - @uh.setter - def uh(self, uh): - if isinstance(uh, np.ndarray): - self.__uh = uh - else: - raise Exception('Invalid uh value.') - - # convex-over-nonlinear constraints - @lphi.setter - def lphi(self, lphi): - if isinstance(lphi, np.ndarray): - self.__lphi = lphi - else: - raise Exception('Invalid lphi value.') - - @uphi.setter - def uphi(self, uphi): - if isinstance(uphi, np.ndarray): - self.__uphi = uphi - else: - raise Exception('Invalid uphi value.') - - # nonlinear constraints at shooting node N - @lh_e.setter - def lh_e(self, lh_e): - if isinstance(lh_e, np.ndarray): - self.__lh_e = lh_e - else: - raise Exception('Invalid lh_e value.') - - @uh_e.setter - def uh_e(self, uh_e): - if isinstance(uh_e, np.ndarray): - self.__uh_e = uh_e - else: - raise Exception('Invalid uh_e value.') - - # convex-over-nonlinear constraints at shooting node N - @lphi_e.setter - def lphi_e(self, lphi_e): - if isinstance(lphi_e, np.ndarray): - self.__lphi_e = lphi_e - else: - raise Exception('Invalid lphi_e value.') - - @uphi_e.setter - def uphi_e(self, uphi_e): - if isinstance(uphi_e, np.ndarray): - self.__uphi_e = uphi_e - else: - raise Exception('Invalid uphi_e value.') - - # SLACK bounds - # soft bounds on x - @lsbx.setter - def lsbx(self, lsbx): - if isinstance(lsbx, np.ndarray): - self.__lsbx = lsbx - else: - raise Exception('Invalid lsbx value.') - - @usbx.setter - def usbx(self, usbx): - if isinstance(usbx, np.ndarray): - self.__usbx = usbx - else: - raise Exception('Invalid usbx value.') - - @idxsbx.setter - def idxsbx(self, idxsbx): - if isinstance(idxsbx, np.ndarray): - self.__idxsbx = idxsbx - else: - raise Exception('Invalid idxsbx value.') - - @Jsbx.setter - def Jsbx(self, Jsbx): - if isinstance(Jsbx, np.ndarray): - self.__idxsbx = J_to_idx_slack(Jsbx) - else: - raise Exception('Invalid Jsbx value, expected numpy array.') - - # soft bounds on u - @lsbu.setter - def lsbu(self, lsbu): - if isinstance(lsbu, np.ndarray): - self.__lsbu = lsbu - else: - raise Exception('Invalid lsbu value.') - - @usbu.setter - def usbu(self, usbu): - if isinstance(usbu, np.ndarray): - self.__usbu = usbu - else: - raise Exception('Invalid usbu value.') - - @idxsbu.setter - def idxsbu(self, idxsbu): - if isinstance(idxsbu, np.ndarray): - self.__idxsbu = idxsbu - else: - raise Exception('Invalid idxsbu value.') - - @Jsbu.setter - def Jsbu(self, Jsbu): - if isinstance(Jsbu, np.ndarray): - self.__idxsbu = J_to_idx_slack(Jsbu) - else: - raise Exception('Invalid Jsbu value.') - - # soft bounds on x at shooting node N - @lsbx_e.setter - def lsbx_e(self, lsbx_e): - if isinstance(lsbx_e, np.ndarray): - self.__lsbx_e = lsbx_e - else: - raise Exception('Invalid lsbx_e value.') - - @usbx_e.setter - def usbx_e(self, usbx_e): - if isinstance(usbx_e, np.ndarray): - self.__usbx_e = usbx_e - else: - raise Exception('Invalid usbx_e value.') - - @idxsbx_e.setter - def idxsbx_e(self, idxsbx_e): - if isinstance(idxsbx_e, np.ndarray): - self.__idxsbx_e = idxsbx_e - else: - raise Exception('Invalid idxsbx_e value.') - - @Jsbx_e.setter - def Jsbx_e(self, Jsbx_e): - if isinstance(Jsbx_e, np.ndarray): - self.__idxsbx_e = J_to_idx_slack(Jsbx_e) - else: - raise Exception('Invalid Jsbx_e value.') - - - # soft bounds on general linear constraints - @lsg.setter - def lsg(self, lsg): - if isinstance(lsg, np.ndarray): - self.__lsg = lsg - else: - raise Exception('Invalid lsg value.') - - @usg.setter - def usg(self, usg): - if isinstance(usg, np.ndarray): - self.__usg = usg - else: - raise Exception('Invalid usg value.') - - @idxsg.setter - def idxsg(self, idxsg): - if isinstance(idxsg, np.ndarray): - self.__idxsg = idxsg - else: - raise Exception('Invalid idxsg value.') - - @Jsg.setter - def Jsg(self, Jsg): - if isinstance(Jsg, np.ndarray): - self.__idxsg = J_to_idx_slack(Jsg) - else: - raise Exception('Invalid Jsg value, expected numpy array.') - - - # soft bounds on nonlinear constraints - @lsh.setter - def lsh(self, lsh): - if isinstance(lsh, np.ndarray): - self.__lsh = lsh - else: - raise Exception('Invalid lsh value.') - - @ush.setter - def ush(self, ush): - if isinstance(ush, np.ndarray): - self.__ush = ush - else: - raise Exception('Invalid ush value.') - - @idxsh.setter - def idxsh(self, idxsh): - if isinstance(idxsh, np.ndarray): - self.__idxsh = idxsh - else: - raise Exception('Invalid idxsh value.') - - - @Jsh.setter - def Jsh(self, Jsh): - if isinstance(Jsh, np.ndarray): - self.__idxsh = J_to_idx_slack(Jsh) - else: - raise Exception('Invalid Jsh value, expected numpy array.') - - # soft bounds on convex-over-nonlinear constraints - @lsphi.setter - def lsphi(self, lsphi): - if isinstance(lsphi, np.ndarray): - self.__lsphi = lsphi - else: - raise Exception('Invalid lsphi value.') - - @usphi.setter - def usphi(self, usphi): - if isinstance(usphi, np.ndarray): - self.__usphi = usphi - else: - raise Exception('Invalid usphi value.') - - @idxsphi.setter - def idxsphi(self, idxsphi): - if isinstance(idxsphi, np.ndarray): - self.__idxsphi = idxsphi - else: - raise Exception('Invalid idxsphi value.') - - @Jsphi.setter - def Jsphi(self, Jsphi): - if isinstance(Jsphi, np.ndarray): - self.__idxsphi = J_to_idx_slack(Jsphi) - else: - raise Exception('Invalid Jsphi value, expected numpy array.') - - # soft bounds on general linear constraints at shooting node N - @lsg_e.setter - def lsg_e(self, lsg_e): - if isinstance(lsg_e, np.ndarray): - self.__lsg_e = lsg_e - else: - raise Exception('Invalid lsg_e value.') - - @usg_e.setter - def usg_e(self, usg_e): - if isinstance(usg_e, np.ndarray): - self.__usg_e = usg_e - else: - raise Exception('Invalid usg_e value.') - - @idxsg_e.setter - def idxsg_e(self, idxsg_e): - if isinstance(idxsg_e, np.ndarray): - self.__idxsg_e = idxsg_e - else: - raise Exception('Invalid idxsg_e value.') - - @Jsg_e.setter - def Jsg_e(self, Jsg_e): - if isinstance(Jsg_e, np.ndarray): - self.__idxsg_e = J_to_idx_slack(Jsg_e) - else: - raise Exception('Invalid Jsg_e value, expected numpy array.') - - # soft bounds on nonlinear constraints at shooting node N - @lsh_e.setter - def lsh_e(self, lsh_e): - if isinstance(lsh_e, np.ndarray): - self.__lsh_e = lsh_e - else: - raise Exception('Invalid lsh_e value.') - - @ush_e.setter - def ush_e(self, ush_e): - if isinstance(ush_e, np.ndarray): - self.__ush_e = ush_e - else: - raise Exception('Invalid ush_e value.') - - @idxsh_e.setter - def idxsh_e(self, idxsh_e): - if isinstance(idxsh_e, np.ndarray): - self.__idxsh_e = idxsh_e - else: - raise Exception('Invalid idxsh_e value.') - - @Jsh_e.setter - def Jsh_e(self, Jsh_e): - if isinstance(Jsh_e, np.ndarray): - self.__idxsh_e = J_to_idx_slack(Jsh_e) - else: - raise Exception('Invalid Jsh_e value, expected numpy array.') - - - # soft bounds on convex-over-nonlinear constraints at shooting node N - @lsphi_e.setter - def lsphi_e(self, lsphi_e): - if isinstance(lsphi_e, np.ndarray): - self.__lsphi_e = lsphi_e - else: - raise Exception('Invalid lsphi_e value.') - - @usphi_e.setter - def usphi_e(self, usphi_e): - if isinstance(usphi_e, np.ndarray): - self.__usphi_e = usphi_e - else: - raise Exception('Invalid usphi_e value.') - - @idxsphi_e.setter - def idxsphi_e(self, idxsphi_e): - if isinstance(idxsphi_e, np.ndarray): - self.__idxsphi_e = idxsphi_e - else: - raise Exception('Invalid idxsphi_e value.') - - @Jsphi_e.setter - def Jsphi_e(self, Jsphi_e): - if isinstance(Jsphi_e, np.ndarray): - self.__idxsphi_e = J_to_idx_slack(Jsphi_e) - else: - raise Exception('Invalid Jsphi_e value.') - - def set(self, attr, value): - setattr(self, attr, value) - - -class AcadosOcpOptions: - """ - class containing the description of the solver options - """ - def __init__(self): - self.__qp_solver = 'PARTIAL_CONDENSING_HPIPM' # qp solver to be used in the NLP solver - self.__hessian_approx = 'GAUSS_NEWTON' # hessian approximation - self.__integrator_type = 'ERK' # integrator type - self.__tf = None # prediction horizon - self.__nlp_solver_type = 'SQP_RTI' # NLP solver - self.__globalization = 'FIXED_STEP' - self.__nlp_solver_step_length = 1.0 # fixed Newton step length - self.__levenberg_marquardt = 0.0 - self.__collocation_type = 'GAUSS_LEGENDRE' - self.__sim_method_num_stages = 4 # number of stages in the integrator - self.__sim_method_num_steps = 1 # number of steps in the integrator - self.__sim_method_newton_iter = 3 # number of Newton iterations in simulation method - self.__sim_method_newton_tol = 0.0 - self.__sim_method_jac_reuse = 0 - self.__qp_solver_tol_stat = None # QP solver stationarity tolerance - self.__qp_solver_tol_eq = None # QP solver equality tolerance - self.__qp_solver_tol_ineq = None # QP solver inequality - self.__qp_solver_tol_comp = None # QP solver complementarity - self.__qp_solver_iter_max = 50 # QP solver max iter - self.__qp_solver_cond_N = None # QP solver: new horizon after partial condensing - self.__qp_solver_warm_start = 0 - self.__qp_solver_cond_ric_alg = 1 - self.__qp_solver_ric_alg = 1 - self.__nlp_solver_tol_stat = 1e-6 # NLP solver stationarity tolerance - self.__nlp_solver_tol_eq = 1e-6 # NLP solver equality tolerance - self.__nlp_solver_tol_ineq = 1e-6 # NLP solver inequality - self.__nlp_solver_tol_comp = 1e-6 # NLP solver complementarity - self.__nlp_solver_max_iter = 100 # NLP solver maximum number of iterations - self.__nlp_solver_ext_qp_res = 0 - self.__Tsim = None # automatically calculated as tf/N - self.__print_level = 0 # print level - self.__initialize_t_slacks = 0 # possible values: 0, 1 - self.__regularize_method = None - self.__time_steps = None - self.__shooting_nodes = None - self.__exact_hess_cost = 1 - self.__exact_hess_dyn = 1 - self.__exact_hess_constr = 1 - self.__ext_cost_num_hess = 0 - self.__alpha_min = 0.05 - self.__alpha_reduction = 0.7 - self.__line_search_use_sufficient_descent = 0 - self.__globalization_use_SOC = 0 - self.__full_step_dual = 0 - self.__eps_sufficient_descent = 1e-4 - self.__hpipm_mode = 'BALANCE' - # TODO: move those out? they are more about generation than about the acados OCP solver. - self.__ext_fun_compile_flags = '-O2' - self.__model_external_shared_lib_dir = None # path to the the .so lib - self.__model_external_shared_lib_name = None # name of the the .so lib - self.__custom_update_filename = '' - self.__custom_update_header_filename = '' - self.__custom_templates = [] - self.__custom_update_copy = True - - @property - def qp_solver(self): - """QP solver to be used in the NLP solver. - String in ('PARTIAL_CONDENSING_HPIPM', 'FULL_CONDENSING_QPOASES', 'FULL_CONDENSING_HPIPM', 'PARTIAL_CONDENSING_QPDUNES', 'PARTIAL_CONDENSING_OSQP', 'FULL_CONDENSING_DAQP'). - Default: 'PARTIAL_CONDENSING_HPIPM'. - """ - return self.__qp_solver - - @property - def ext_fun_compile_flags(self): - """ - String with compiler flags for external function compilation. - Default: '-O2'. - """ - return self.__ext_fun_compile_flags - - - @property - def custom_update_filename(self): - """ - Filename of the custom C function to update solver data and parameters in between solver calls - - This file has to implement the functions - int custom_update_init_function([model.name]_solver_capsule* capsule); - int custom_update_function([model.name]_solver_capsule* capsule); - int custom_update_terminate_function([model.name]_solver_capsule* capsule); - - - Default: ''. - """ - return self.__custom_update_filename - - - @property - def custom_templates(self): - """ - List of tuples of the form: - (input_filename, output_filename) - - Custom templates are render in OCP solver generation. - - Default: []. - """ - return self.__custom_templates - - - @property - def custom_update_header_filename(self): - """ - Header filename of the custom C function to update solver data and parameters in between solver calls - - This file has to declare the custom_update functions and look as follows: - - ``` - // Called at the end of solver creation. - // This is allowed to allocate memory and store the pointer to it into capsule->custom_update_memory. - int custom_update_init_function([model.name]_solver_capsule* capsule); - - // Custom update function that can be called between solver calls - int custom_update_function([model.name]_solver_capsule* capsule, double* data, int data_len); - - // Called just before destroying the solver. - // Responsible to free allocated memory, stored at capsule->custom_update_memory. - int custom_update_terminate_function([model.name]_solver_capsule* capsule); - - Default: ''. - """ - return self.__custom_update_header_filename - - @property - def custom_update_copy(self): - """ - Boolean; - If True, the custom update function files are copied into the `code_export_directory`. - """ - return self.__custom_update_copy - - - @property - def hpipm_mode(self): - """ - Mode of HPIPM to be used, - - String in ('BALANCE', 'SPEED_ABS', 'SPEED', 'ROBUST'). - - Default: 'BALANCE'. - - see https://cdn.syscop.de/publications/Frison2020a.pdf - and the HPIPM code: - https://github.com/giaf/hpipm/blob/master/ocp_qp/x_ocp_qp_ipm.c#L69 - """ - return self.__hpipm_mode - - @property - def hessian_approx(self): - """Hessian approximation. - String in ('GAUSS_NEWTON', 'EXACT'). - Default: 'GAUSS_NEWTON'. - """ - return self.__hessian_approx - - @property - def integrator_type(self): - """ - Integrator type. - String in ('ERK', 'IRK', 'GNSF', 'DISCRETE', 'LIFTED_IRK'). - Default: 'ERK'. - """ - return self.__integrator_type - - @property - def nlp_solver_type(self): - """NLP solver. - String in ('SQP', 'SQP_RTI'). - Default: 'SQP_RTI'. - """ - return self.__nlp_solver_type - - @property - def globalization(self): - """Globalization type. - String in ('FIXED_STEP', 'MERIT_BACKTRACKING'). - Default: 'FIXED_STEP'. - - .. note:: preliminary implementation. - """ - return self.__globalization - - @property - def collocation_type(self): - """Collocation type: relevant for implicit integrators - -- string in {GAUSS_RADAU_IIA, GAUSS_LEGENDRE}. - - Default: GAUSS_LEGENDRE - """ - return self.__collocation_type - - @property - def regularize_method(self): - """Regularization method for the Hessian. - String in ('NO_REGULARIZE', 'MIRROR', 'PROJECT', 'PROJECT_REDUC_HESS', 'CONVEXIFY') or :code:`None`. - - - MIRROR: performs eigenvalue decomposition H = V^T D V and sets D_ii = max(eps, abs(D_ii)) - - PROJECT: performs eigenvalue decomposition H = V^T D V and sets D_ii = max(eps, D_ii) - - CONVEXIFY: Algorithm 6 from Verschueren2017, https://cdn.syscop.de/publications/Verschueren2017.pdf - - PROJECT_REDUC_HESS: experimental - - Note: default eps = 1e-4 - - Default: :code:`None`. - """ - return self.__regularize_method - - @property - def nlp_solver_step_length(self): - """ - Fixed Newton step length. - Type: float > 0. - Default: 1.0. - """ - return self.__nlp_solver_step_length - - @property - def levenberg_marquardt(self): - """ - Factor for LM regularization. - Type: float >= 0 - Default: 0.0. - """ - return self.__levenberg_marquardt - - @property - def sim_method_num_stages(self): - """ - Number of stages in the integrator. - Type: int > 0 or ndarray of ints > 0 of shape (N,). - Default: 4 - """ - return self.__sim_method_num_stages - - @property - def sim_method_num_steps(self): - """ - Number of steps in the integrator. - Type: int > 0 or ndarray of ints > 0 of shape (N,). - Default: 1 - """ - return self.__sim_method_num_steps - - @property - def sim_method_newton_iter(self): - """ - Number of Newton iterations in simulation method. - Type: int > 0 - Default: 3 - """ - return self.__sim_method_newton_iter - - @property - def sim_method_newton_tol(self): - """ - Tolerance of Newton system in simulation method. - Type: float: 0.0 means not used - Default: 0.0 - """ - return self.__sim_method_newton_tol - - @property - def sim_method_jac_reuse(self): - """ - Integer determining if jacobians are reused within integrator or ndarray of ints > 0 of shape (N,). - 0: False (no reuse); 1: True (reuse) - Default: 0 - """ - return self.__sim_method_jac_reuse - - @property - def qp_solver_tol_stat(self): - """ - QP solver stationarity tolerance. - Default: :code:`None` - """ - return self.__qp_solver_tol_stat - - @property - def qp_solver_tol_eq(self): - """ - QP solver equality tolerance. - Default: :code:`None` - """ - return self.__qp_solver_tol_eq - - @property - def qp_solver_tol_ineq(self): - """ - QP solver inequality. - Default: :code:`None` - """ - return self.__qp_solver_tol_ineq - - @property - def qp_solver_tol_comp(self): - """ - QP solver complementarity. - Default: :code:`None` - """ - return self.__qp_solver_tol_comp - - @property - def qp_solver_cond_N(self): - """QP solver: New horizon after partial condensing. - Set to N by default -> no condensing.""" - return self.__qp_solver_cond_N - - @property - def qp_solver_warm_start(self): - """ - QP solver: Warm starting. - 0: no warm start; 1: warm start; 2: hot start. - Default: 0 - """ - return self.__qp_solver_warm_start - - @property - def qp_solver_cond_ric_alg(self): - """ - QP solver: Determines which algorithm is used in HPIPM condensing. - 0: dont factorize hessian in the condensing; 1: factorize. - Default: 1 - """ - return self.__qp_solver_cond_ric_alg - - @property - def qp_solver_ric_alg(self): - """ - QP solver: Determines which algorithm is used in HPIPM OCP QP solver. - 0 classical Riccati, 1 square-root Riccati. - - Note: taken from [HPIPM paper]: - - (a) the classical implementation requires the reduced Hessian with respect to the dynamics - equality constraints to be positive definite, but allows the full-space Hessian to be indefinite) - (b) the square-root implementation, which in order to reduce the flop count employs the Cholesky - factorization of the Riccati recursion matrix, and therefore requires the full-space Hessian to be positive definite - - [HPIPM paper]: HPIPM: a high-performance quadratic programming framework for model predictive control, Frison and Diehl, 2020 - https://cdn.syscop.de/publications/Frison2020a.pdf - - Default: 1 - """ - return self.__qp_solver_ric_alg - - @property - def qp_solver_iter_max(self): - """ - QP solver: maximum number of iterations. - Type: int > 0 - Default: 50 - """ - return self.__qp_solver_iter_max - - @property - def tol(self): - """ - NLP solver tolerance. Sets or gets the max of :py:attr:`nlp_solver_tol_eq`, - :py:attr:`nlp_solver_tol_ineq`, :py:attr:`nlp_solver_tol_comp` - and :py:attr:`nlp_solver_tol_stat`. - """ - return max([self.__nlp_solver_tol_eq, self.__nlp_solver_tol_ineq,\ - self.__nlp_solver_tol_comp, self.__nlp_solver_tol_stat]) - - @property - def qp_tol(self): - """ - QP solver tolerance. - Sets all of the following at once or gets the max of - :py:attr:`qp_solver_tol_eq`, :py:attr:`qp_solver_tol_ineq`, - :py:attr:`qp_solver_tol_comp` and - :py:attr:`qp_solver_tol_stat`. - """ - return max([self.__qp_solver_tol_eq, self.__qp_solver_tol_ineq,\ - self.__qp_solver_tol_comp, self.__qp_solver_tol_stat]) - - @property - def nlp_solver_tol_stat(self): - """ - NLP solver stationarity tolerance. - Type: float > 0 - Default: 1e-6 - """ - return self.__nlp_solver_tol_stat - - @property - def nlp_solver_tol_eq(self): - """NLP solver equality tolerance""" - return self.__nlp_solver_tol_eq - - @property - def alpha_min(self): - """Minimal step size for globalization MERIT_BACKTRACKING, default: 0.05.""" - return self.__alpha_min - - @property - def alpha_reduction(self): - """Step size reduction factor for globalization MERIT_BACKTRACKING, default: 0.7.""" - return self.__alpha_reduction - - @property - def line_search_use_sufficient_descent(self): - """ - Determines if sufficient descent (Armijo) condition is used in line search. - Type: int; 0 or 1; - default: 0. - """ - return self.__line_search_use_sufficient_descent - - @property - def eps_sufficient_descent(self): - """ - Factor for sufficient descent (Armijo) conditon, see line_search_use_sufficient_descent. - Type: float, - default: 1e-4. - """ - return self.__eps_sufficient_descent - - @property - def globalization_use_SOC(self): - """ - Determines if second order correction (SOC) is done when using MERIT_BACKTRACKING. - SOC is done if preliminary line search does not return full step. - Type: int; 0 or 1; - default: 0. - """ - return self.__globalization_use_SOC - - @property - def full_step_dual(self): - """ - Determines if dual variables are updated with full steps (alpha=1.0) when primal variables are updated with smaller step. - Type: int; 0 or 1; - default: 0. - """ - return self.__full_step_dual - - @property - def nlp_solver_tol_ineq(self): - """NLP solver inequality tolerance""" - return self.__nlp_solver_tol_ineq - - @property - def nlp_solver_ext_qp_res(self): - """Determines if residuals of QP are computed externally within NLP solver (for debugging) - - Type: int; 0 or 1; - Default: 0. - """ - return self.__nlp_solver_ext_qp_res - - @property - def nlp_solver_tol_comp(self): - """NLP solver complementarity tolerance""" - return self.__nlp_solver_tol_comp - - @property - def nlp_solver_max_iter(self): - """ - NLP solver maximum number of iterations. - Type: int > 0 - Default: 100 - """ - return self.__nlp_solver_max_iter - - @property - def time_steps(self): - """ - Vector with time steps between the shooting nodes. Set automatically to uniform discretization if :py:attr:`N` and :py:attr:`tf` are provided. - Default: :code:`None` - """ - return self.__time_steps - - @property - def shooting_nodes(self): - """ - Vector with the shooting nodes, time_steps will be computed from it automatically. - Default: :code:`None` - """ - return self.__shooting_nodes - - @property - def tf(self): - """ - Prediction horizon - Type: float > 0 - Default: :code:`None` - """ - return self.__tf - - @property - def Tsim(self): - """ - Time horizon for one integrator step. Automatically calculated as :py:attr:`tf`/:py:attr:`N`. - Default: :code:`None` - """ - return self.__Tsim - - @property - def print_level(self): - """ - Verbosity of printing. - Type: int >= 0 - Default: 0 - """ - return self.__print_level - - @property - def model_external_shared_lib_dir(self): - """Path to the .so lib""" - return self.__model_external_shared_lib_dir - - @property - def model_external_shared_lib_name(self): - """Name of the .so lib""" - return self.__model_external_shared_lib_name - - @property - def exact_hess_constr(self): - """ - Used in case of hessian_approx == 'EXACT'.\n - Can be used to turn off exact hessian contributions from the constraints module. - """ - return self.__exact_hess_constr - - @property - def exact_hess_cost(self): - """ - Used in case of hessian_approx == 'EXACT'.\n - Can be used to turn off exact hessian contributions from the cost module. - """ - return self.__exact_hess_cost - - @property - def exact_hess_dyn(self): - """ - Used in case of hessian_approx == 'EXACT'.\n - Can be used to turn off exact hessian contributions from the dynamics module. - """ - return self.__exact_hess_dyn - - @property - def ext_cost_num_hess(self): - """ - Determines if custom hessian approximation for cost contribution is used (> 0).\n - Or if hessian contribution is evaluated exactly using CasADi external function (=0 - default). - """ - return self.__ext_cost_num_hess - - @qp_solver.setter - def qp_solver(self, qp_solver): - qp_solvers = ('PARTIAL_CONDENSING_HPIPM', \ - 'FULL_CONDENSING_QPOASES', 'FULL_CONDENSING_HPIPM', \ - 'PARTIAL_CONDENSING_QPDUNES', 'PARTIAL_CONDENSING_OSQP', \ - 'FULL_CONDENSING_DAQP') - if qp_solver in qp_solvers: - self.__qp_solver = qp_solver - else: - raise Exception('Invalid qp_solver value. Possible values are:\n\n' \ - + ',\n'.join(qp_solvers) + '.\n\nYou have: ' + qp_solver + '.\n\n') - - @regularize_method.setter - def regularize_method(self, regularize_method): - regularize_methods = ('NO_REGULARIZE', 'MIRROR', 'PROJECT', \ - 'PROJECT_REDUC_HESS', 'CONVEXIFY') - if regularize_method in regularize_methods: - self.__regularize_method = regularize_method - else: - raise Exception('Invalid regularize_method value. Possible values are:\n\n' \ - + ',\n'.join(regularize_methods) + '.\n\nYou have: ' + regularize_method + '.\n\n') - - @collocation_type.setter - def collocation_type(self, collocation_type): - collocation_types = ('GAUSS_RADAU_IIA', 'GAUSS_LEGENDRE') - if collocation_type in collocation_types: - self.__collocation_type = collocation_type - else: - raise Exception('Invalid collocation_type value. Possible values are:\n\n' \ - + ',\n'.join(collocation_types) + '.\n\nYou have: ' + collocation_type + '.\n\n') - - @hpipm_mode.setter - def hpipm_mode(self, hpipm_mode): - hpipm_modes = ('BALANCE', 'SPEED_ABS', 'SPEED', 'ROBUST') - if hpipm_mode in hpipm_modes: - self.__hpipm_mode = hpipm_mode - else: - raise Exception('Invalid hpipm_mode value. Possible values are:\n\n' \ - + ',\n'.join(hpipm_modes) + '.\n\nYou have: ' + hpipm_mode + '.\n\n') - - @ext_fun_compile_flags.setter - def ext_fun_compile_flags(self, ext_fun_compile_flags): - if isinstance(ext_fun_compile_flags, str): - self.__ext_fun_compile_flags = ext_fun_compile_flags - else: - raise Exception('Invalid ext_fun_compile_flags, expected a string.\n') - - - @custom_update_filename.setter - def custom_update_filename(self, custom_update_filename): - if isinstance(custom_update_filename, str): - self.__custom_update_filename = custom_update_filename - else: - raise Exception('Invalid custom_update_filename, expected a string.\n') - - @custom_templates.setter - def custom_templates(self, custom_templates): - if not isinstance(custom_templates, list): - raise Exception('Invalid custom_templates, expected a list.\n') - for tup in custom_templates: - if not isinstance(tup, tuple): - raise Exception('Invalid custom_templates, shoubld be list of tuples.\n') - for s in tup: - if not isinstance(s, str): - raise Exception('Invalid custom_templates, shoubld be list of tuples of strings.\n') - self.__custom_templates = custom_templates - - @custom_update_header_filename.setter - def custom_update_header_filename(self, custom_update_header_filename): - if isinstance(custom_update_header_filename, str): - self.__custom_update_header_filename = custom_update_header_filename - else: - raise Exception('Invalid custom_update_header_filename, expected a string.\n') - - @custom_update_copy.setter - def custom_update_copy(self, custom_update_copy): - if isinstance(custom_update_copy, bool): - self.__custom_update_copy = custom_update_copy - else: - raise Exception('Invalid custom_update_copy, expected a bool.\n') - - @hessian_approx.setter - def hessian_approx(self, hessian_approx): - hessian_approxs = ('GAUSS_NEWTON', 'EXACT') - if hessian_approx in hessian_approxs: - self.__hessian_approx = hessian_approx - else: - raise Exception('Invalid hessian_approx value. Possible values are:\n\n' \ - + ',\n'.join(hessian_approxs) + '.\n\nYou have: ' + hessian_approx + '.\n\n') - - @integrator_type.setter - def integrator_type(self, integrator_type): - integrator_types = ('ERK', 'IRK', 'GNSF', 'DISCRETE', 'LIFTED_IRK') - if integrator_type in integrator_types: - self.__integrator_type = integrator_type - else: - raise Exception('Invalid integrator_type value. Possible values are:\n\n' \ - + ',\n'.join(integrator_types) + '.\n\nYou have: ' + integrator_type + '.\n\n') - - @tf.setter - def tf(self, tf): - self.__tf = tf - - @time_steps.setter - def time_steps(self, time_steps): - if isinstance(time_steps, np.ndarray): - if len(time_steps.shape) == 1: - self.__time_steps = time_steps - else: - raise Exception('Invalid time_steps, expected np.ndarray of shape (N,).') - else: - raise Exception('Invalid time_steps, expected np.ndarray.') - - @shooting_nodes.setter - def shooting_nodes(self, shooting_nodes): - if isinstance(shooting_nodes, np.ndarray): - if len(shooting_nodes.shape) == 1: - self.__shooting_nodes = shooting_nodes - else: - raise Exception('Invalid shooting_nodes, expected np.ndarray of shape (N+1,).') - else: - raise Exception('Invalid shooting_nodes, expected np.ndarray.') - - @Tsim.setter - def Tsim(self, Tsim): - self.__Tsim = Tsim - - @globalization.setter - def globalization(self, globalization): - globalization_types = ('MERIT_BACKTRACKING', 'FIXED_STEP') - if globalization in globalization_types: - self.__globalization = globalization - else: - raise Exception('Invalid globalization value. Possible values are:\n\n' \ - + ',\n'.join(globalization_types) + '.\n\nYou have: ' + globalization + '.\n\n') - - @alpha_min.setter - def alpha_min(self, alpha_min): - self.__alpha_min = alpha_min - - @alpha_reduction.setter - def alpha_reduction(self, alpha_reduction): - self.__alpha_reduction = alpha_reduction - - @line_search_use_sufficient_descent.setter - def line_search_use_sufficient_descent(self, line_search_use_sufficient_descent): - if line_search_use_sufficient_descent in [0, 1]: - self.__line_search_use_sufficient_descent = line_search_use_sufficient_descent - else: - raise Exception(f'Invalid value for line_search_use_sufficient_descent. Possible values are 0, 1, got {line_search_use_sufficient_descent}') - - @globalization_use_SOC.setter - def globalization_use_SOC(self, globalization_use_SOC): - if globalization_use_SOC in [0, 1]: - self.__globalization_use_SOC = globalization_use_SOC - else: - raise Exception(f'Invalid value for globalization_use_SOC. Possible values are 0, 1, got {globalization_use_SOC}') - - @full_step_dual.setter - def full_step_dual(self, full_step_dual): - if full_step_dual in [0, 1]: - self.__full_step_dual = full_step_dual - else: - raise Exception(f'Invalid value for full_step_dual. Possible values are 0, 1, got {full_step_dual}') - - @eps_sufficient_descent.setter - def eps_sufficient_descent(self, eps_sufficient_descent): - if isinstance(eps_sufficient_descent, float) and eps_sufficient_descent > 0: - self.__eps_sufficient_descent = eps_sufficient_descent - else: - raise Exception('Invalid eps_sufficient_descent value. eps_sufficient_descent must be a positive float.') - - @sim_method_num_stages.setter - def sim_method_num_stages(self, sim_method_num_stages): - - # if isinstance(sim_method_num_stages, int): - # self.__sim_method_num_stages = sim_method_num_stages - # else: - # raise Exception('Invalid sim_method_num_stages value. sim_method_num_stages must be an integer.') - - self.__sim_method_num_stages = sim_method_num_stages - - @sim_method_num_steps.setter - def sim_method_num_steps(self, sim_method_num_steps): - - # if isinstance(sim_method_num_steps, int): - # self.__sim_method_num_steps = sim_method_num_steps - # else: - # raise Exception('Invalid sim_method_num_steps value. sim_method_num_steps must be an integer.') - self.__sim_method_num_steps = sim_method_num_steps - - - @sim_method_newton_iter.setter - def sim_method_newton_iter(self, sim_method_newton_iter): - - if isinstance(sim_method_newton_iter, int): - self.__sim_method_newton_iter = sim_method_newton_iter - else: - raise Exception('Invalid sim_method_newton_iter value. sim_method_newton_iter must be an integer.') - - @sim_method_jac_reuse.setter - def sim_method_jac_reuse(self, sim_method_jac_reuse): - # if sim_method_jac_reuse in (True, False): - self.__sim_method_jac_reuse = sim_method_jac_reuse - # else: - # raise Exception('Invalid sim_method_jac_reuse value. sim_method_jac_reuse must be a Boolean.') - - @nlp_solver_type.setter - def nlp_solver_type(self, nlp_solver_type): - nlp_solver_types = ('SQP', 'SQP_RTI') - if nlp_solver_type in nlp_solver_types: - self.__nlp_solver_type = nlp_solver_type - else: - raise Exception('Invalid nlp_solver_type value. Possible values are:\n\n' \ - + ',\n'.join(nlp_solver_types) + '.\n\nYou have: ' + nlp_solver_type + '.\n\n') - - @nlp_solver_step_length.setter - def nlp_solver_step_length(self, nlp_solver_step_length): - if isinstance(nlp_solver_step_length, float) and nlp_solver_step_length > 0: - self.__nlp_solver_step_length = nlp_solver_step_length - else: - raise Exception('Invalid nlp_solver_step_length value. nlp_solver_step_length must be a positive float.') - - @levenberg_marquardt.setter - def levenberg_marquardt(self, levenberg_marquardt): - if isinstance(levenberg_marquardt, float) and levenberg_marquardt >= 0: - self.__levenberg_marquardt = levenberg_marquardt - else: - raise Exception('Invalid levenberg_marquardt value. levenberg_marquardt must be a positive float.') - - @qp_solver_iter_max.setter - def qp_solver_iter_max(self, qp_solver_iter_max): - if isinstance(qp_solver_iter_max, int) and qp_solver_iter_max > 0: - self.__qp_solver_iter_max = qp_solver_iter_max - else: - raise Exception('Invalid qp_solver_iter_max value. qp_solver_iter_max must be a positive int.') - - @qp_solver_ric_alg.setter - def qp_solver_ric_alg(self, qp_solver_ric_alg): - if qp_solver_ric_alg in [0, 1]: - self.__qp_solver_ric_alg = qp_solver_ric_alg - else: - raise Exception(f'Invalid qp_solver_ric_alg value. qp_solver_ric_alg must be in [0, 1], got {qp_solver_ric_alg}.') - - @qp_solver_cond_ric_alg.setter - def qp_solver_cond_ric_alg(self, qp_solver_cond_ric_alg): - if qp_solver_cond_ric_alg in [0, 1]: - self.__qp_solver_cond_ric_alg = qp_solver_cond_ric_alg - else: - raise Exception(f'Invalid qp_solver_cond_ric_alg value. qp_solver_cond_ric_alg must be in [0, 1], got {qp_solver_cond_ric_alg}.') - - - @qp_solver_cond_N.setter - def qp_solver_cond_N(self, qp_solver_cond_N): - if isinstance(qp_solver_cond_N, int) and qp_solver_cond_N >= 0: - self.__qp_solver_cond_N = qp_solver_cond_N - else: - raise Exception('Invalid qp_solver_cond_N value. qp_solver_cond_N must be a positive int.') - - @qp_solver_warm_start.setter - def qp_solver_warm_start(self, qp_solver_warm_start): - if qp_solver_warm_start in [0, 1, 2]: - self.__qp_solver_warm_start = qp_solver_warm_start - else: - raise Exception('Invalid qp_solver_warm_start value. qp_solver_warm_start must be 0 or 1 or 2.') - - @qp_tol.setter - def qp_tol(self, qp_tol): - if isinstance(qp_tol, float) and qp_tol > 0: - self.__qp_solver_tol_eq = qp_tol - self.__qp_solver_tol_ineq = qp_tol - self.__qp_solver_tol_stat = qp_tol - self.__qp_solver_tol_comp = qp_tol - else: - raise Exception('Invalid qp_tol value. qp_tol must be a positive float.') - - @qp_solver_tol_stat.setter - def qp_solver_tol_stat(self, qp_solver_tol_stat): - if isinstance(qp_solver_tol_stat, float) and qp_solver_tol_stat > 0: - self.__qp_solver_tol_stat = qp_solver_tol_stat - else: - raise Exception('Invalid qp_solver_tol_stat value. qp_solver_tol_stat must be a positive float.') - - @qp_solver_tol_eq.setter - def qp_solver_tol_eq(self, qp_solver_tol_eq): - if isinstance(qp_solver_tol_eq, float) and qp_solver_tol_eq > 0: - self.__qp_solver_tol_eq = qp_solver_tol_eq - else: - raise Exception('Invalid qp_solver_tol_eq value. qp_solver_tol_eq must be a positive float.') - - @qp_solver_tol_ineq.setter - def qp_solver_tol_ineq(self, qp_solver_tol_ineq): - if isinstance(qp_solver_tol_ineq, float) and qp_solver_tol_ineq > 0: - self.__qp_solver_tol_ineq = qp_solver_tol_ineq - else: - raise Exception('Invalid qp_solver_tol_ineq value. qp_solver_tol_ineq must be a positive float.') - - @qp_solver_tol_comp.setter - def qp_solver_tol_comp(self, qp_solver_tol_comp): - if isinstance(qp_solver_tol_comp, float) and qp_solver_tol_comp > 0: - self.__qp_solver_tol_comp = qp_solver_tol_comp - else: - raise Exception('Invalid qp_solver_tol_comp value. qp_solver_tol_comp must be a positive float.') - - @tol.setter - def tol(self, tol): - if isinstance(tol, float) and tol > 0: - self.__nlp_solver_tol_eq = tol - self.__nlp_solver_tol_ineq = tol - self.__nlp_solver_tol_stat = tol - self.__nlp_solver_tol_comp = tol - else: - raise Exception('Invalid tol value. tol must be a positive float.') - - @nlp_solver_tol_stat.setter - def nlp_solver_tol_stat(self, nlp_solver_tol_stat): - if isinstance(nlp_solver_tol_stat, float) and nlp_solver_tol_stat > 0: - self.__nlp_solver_tol_stat = nlp_solver_tol_stat - else: - raise Exception('Invalid nlp_solver_tol_stat value. nlp_solver_tol_stat must be a positive float.') - - @nlp_solver_tol_eq.setter - def nlp_solver_tol_eq(self, nlp_solver_tol_eq): - if isinstance(nlp_solver_tol_eq, float) and nlp_solver_tol_eq > 0: - self.__nlp_solver_tol_eq = nlp_solver_tol_eq - else: - raise Exception('Invalid nlp_solver_tol_eq value. nlp_solver_tol_eq must be a positive float.') - - @nlp_solver_tol_ineq.setter - def nlp_solver_tol_ineq(self, nlp_solver_tol_ineq): - if isinstance(nlp_solver_tol_ineq, float) and nlp_solver_tol_ineq > 0: - self.__nlp_solver_tol_ineq = nlp_solver_tol_ineq - else: - raise Exception('Invalid nlp_solver_tol_ineq value. nlp_solver_tol_ineq must be a positive float.') - - @nlp_solver_ext_qp_res.setter - def nlp_solver_ext_qp_res(self, nlp_solver_ext_qp_res): - if nlp_solver_ext_qp_res in [0, 1]: - self.__nlp_solver_ext_qp_res = nlp_solver_ext_qp_res - else: - raise Exception('Invalid nlp_solver_ext_qp_res value. nlp_solver_ext_qp_res must be in [0, 1].') - - @nlp_solver_tol_comp.setter - def nlp_solver_tol_comp(self, nlp_solver_tol_comp): - if isinstance(nlp_solver_tol_comp, float) and nlp_solver_tol_comp > 0: - self.__nlp_solver_tol_comp = nlp_solver_tol_comp - else: - raise Exception('Invalid nlp_solver_tol_comp value. nlp_solver_tol_comp must be a positive float.') - - @nlp_solver_max_iter.setter - def nlp_solver_max_iter(self, nlp_solver_max_iter): - - if isinstance(nlp_solver_max_iter, int) and nlp_solver_max_iter > 0: - self.__nlp_solver_max_iter = nlp_solver_max_iter - else: - raise Exception('Invalid nlp_solver_max_iter value. nlp_solver_max_iter must be a positive int.') - - @print_level.setter - def print_level(self, print_level): - if isinstance(print_level, int) and print_level >= 0: - self.__print_level = print_level - else: - raise Exception('Invalid print_level value. print_level takes one of the values >=0.') - - @model_external_shared_lib_dir.setter - def model_external_shared_lib_dir(self, model_external_shared_lib_dir): - if isinstance(model_external_shared_lib_dir, str) : - self.__model_external_shared_lib_dir = model_external_shared_lib_dir - else: - raise Exception('Invalid model_external_shared_lib_dir value. Str expected.' \ - + '.\n\nYou have: ' + type(model_external_shared_lib_dir) + '.\n\n') - - @model_external_shared_lib_name.setter - def model_external_shared_lib_name(self, model_external_shared_lib_name): - if isinstance(model_external_shared_lib_name, str) : - if model_external_shared_lib_name[-3:] == '.so' : - raise Exception('Invalid model_external_shared_lib_name value. Remove the .so extension.' \ - + '.\n\nYou have: ' + type(model_external_shared_lib_name) + '.\n\n') - else : - self.__model_external_shared_lib_name = model_external_shared_lib_name - else: - raise Exception('Invalid model_external_shared_lib_name value. Str expected.' \ - + '.\n\nYou have: ' + type(model_external_shared_lib_name) + '.\n\n') - - @exact_hess_constr.setter - def exact_hess_constr(self, exact_hess_constr): - if exact_hess_constr in [0, 1]: - self.__exact_hess_constr = exact_hess_constr - else: - raise Exception('Invalid exact_hess_constr value. exact_hess_constr takes one of the values 0, 1.') - - @exact_hess_cost.setter - def exact_hess_cost(self, exact_hess_cost): - if exact_hess_cost in [0, 1]: - self.__exact_hess_cost = exact_hess_cost - else: - raise Exception('Invalid exact_hess_cost value. exact_hess_cost takes one of the values 0, 1.') - - @exact_hess_dyn.setter - def exact_hess_dyn(self, exact_hess_dyn): - if exact_hess_dyn in [0, 1]: - self.__exact_hess_dyn = exact_hess_dyn - else: - raise Exception('Invalid exact_hess_dyn value. exact_hess_dyn takes one of the values 0, 1.') - - @ext_cost_num_hess.setter - def ext_cost_num_hess(self, ext_cost_num_hess): - if ext_cost_num_hess in [0, 1]: - self.__ext_cost_num_hess = ext_cost_num_hess - else: - raise Exception('Invalid ext_cost_num_hess value. ext_cost_num_hess takes one of the values 0, 1.') - - def set(self, attr, value): - setattr(self, attr, value) - - -class AcadosOcp: - """ - Class containing the full description of the optimal control problem. - This object can be used to create an :py:class:`acados_template.acados_ocp_solver.AcadosOcpSolver`. - - The class has the following properties that can be modified to formulate a specific OCP, see below: - - - :py:attr:`dims` of type :py:class:`acados_template.acados_ocp.AcadosOcpDims` - - :py:attr:`model` of type :py:class:`acados_template.acados_model.AcadosModel` - - :py:attr:`cost` of type :py:class:`acados_template.acados_ocp.AcadosOcpCost` - - :py:attr:`constraints` of type :py:class:`acados_template.acados_ocp.AcadosOcpConstraints` - - :py:attr:`solver_options` of type :py:class:`acados_template.acados_ocp.AcadosOcpOptions` - - - :py:attr:`acados_include_path` (set automatically) - - :py:attr:`shared_lib_ext` (set automatically) - - :py:attr:`acados_lib_path` (set automatically) - - :py:attr:`parameter_values` - used to initialize the parameters (can be changed) - """ - def __init__(self, acados_path=''): - """ - Keyword arguments: - acados_path -- path of your acados installation - """ - if acados_path == '': - acados_path = get_acados_path() - - self.dims = AcadosOcpDims() - """Dimension definitions, type :py:class:`acados_template.acados_ocp.AcadosOcpDims`""" - self.model = AcadosModel() - """Model definitions, type :py:class:`acados_template.acados_model.AcadosModel`""" - self.cost = AcadosOcpCost() - """Cost definitions, type :py:class:`acados_template.acados_ocp.AcadosOcpCost`""" - self.constraints = AcadosOcpConstraints() - """Constraints definitions, type :py:class:`acados_template.acados_ocp.AcadosOcpConstraints`""" - self.solver_options = AcadosOcpOptions() - """Solver Options, type :py:class:`acados_template.acados_ocp.AcadosOcpOptions`""" - - self.acados_include_path = os.path.join(acados_path, 'include').replace(os.sep, '/') # the replace part is important on Windows for CMake - """Path to acados include directory (set automatically), type: `string`""" - self.acados_lib_path = os.path.join(acados_path, 'lib').replace(os.sep, '/') # the replace part is important on Windows for CMake - """Path to where acados library is located, type: `string`""" - self.shared_lib_ext = get_lib_ext() - - # get cython paths - from sysconfig import get_paths - self.cython_include_dirs = [np.get_include(), get_paths()['include']] - - self.__parameter_values = np.array([]) - self.__problem_class = 'OCP' - - self.code_export_directory = 'c_generated_code' - """Path to where code will be exported. Default: `c_generated_code`.""" - - @property - def parameter_values(self): - """:math:`p` - initial values for parameter - can be updated stagewise""" - return self.__parameter_values - - @parameter_values.setter - def parameter_values(self, parameter_values): - if isinstance(parameter_values, np.ndarray): - self.__parameter_values = parameter_values - else: - raise Exception('Invalid parameter_values value. ' + - f'Expected numpy array, got {type(parameter_values)}.') - - def set(self, attr, value): - # tokenize string - tokens = attr.split('_', 1) - if len(tokens) > 1: - setter_to_call = getattr(getattr(self, tokens[0]), 'set') - else: - setter_to_call = getattr(self, 'set') - - setter_to_call(tokens[1], value) - - return diff --git a/third_party/acados/acados_template/acados_ocp_solver.py b/third_party/acados/acados_template/acados_ocp_solver.py deleted file mode 100644 index 229bdf6039..0000000000 --- a/third_party/acados/acados_template/acados_ocp_solver.py +++ /dev/null @@ -1,1990 +0,0 @@ -# -# Copyright (c) The acados authors. -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# - -import sys -import os -import json -import numpy as np -from datetime import datetime -import importlib -import shutil - -from subprocess import DEVNULL, call, STDOUT - -from ctypes import POINTER, cast, CDLL, c_void_p, c_char_p, c_double, c_int, c_int64, byref - -from copy import deepcopy -from pathlib import Path - -from .casadi_function_generation import generate_c_code_explicit_ode, \ - generate_c_code_implicit_ode, generate_c_code_gnsf, generate_c_code_discrete_dynamics, \ - generate_c_code_constraint, generate_c_code_nls_cost, generate_c_code_conl_cost, \ - generate_c_code_external_cost -from .gnsf.detect_gnsf_structure import detect_gnsf_structure -from .acados_ocp import AcadosOcp -from .acados_model import AcadosModel -from .utils import is_column, is_empty, casadi_length, render_template,\ - format_class_dict, make_object_json_dumpable, make_model_consistent,\ - set_up_imported_gnsf_model, get_ocp_nlp_layout, get_python_interface_path, get_lib_ext, check_casadi_version -from .builders import CMakeBuilder - - -def make_ocp_dims_consistent(acados_ocp: AcadosOcp): - dims = acados_ocp.dims - cost = acados_ocp.cost - constraints = acados_ocp.constraints - model = acados_ocp.model - opts = acados_ocp.solver_options - - # nx - if is_column(model.x): - dims.nx = casadi_length(model.x) - else: - raise Exception('model.x should be column vector!') - - # nu - if is_empty(model.u): - dims.nu = 0 - else: - dims.nu = casadi_length(model.u) - - # nz - if is_empty(model.z): - dims.nz = 0 - else: - dims.nz = casadi_length(model.z) - - # np - if is_empty(model.p): - dims.np = 0 - else: - dims.np = casadi_length(model.p) - if acados_ocp.parameter_values.shape[0] != dims.np: - raise Exception('inconsistent dimension np, regarding model.p and parameter_values.' + \ - f'\nGot np = {dims.np}, acados_ocp.parameter_values.shape = {acados_ocp.parameter_values.shape[0]}\n') - - ## cost - # initial stage - if not set, copy fields from path constraints - if cost.cost_type_0 is None: - cost.cost_type_0 = cost.cost_type - cost.W_0 = cost.W - cost.Vx_0 = cost.Vx - cost.Vu_0 = cost.Vu - cost.Vz_0 = cost.Vz - cost.yref_0 = cost.yref - cost.cost_ext_fun_type_0 = cost.cost_ext_fun_type - model.cost_y_expr_0 = model.cost_y_expr - model.cost_expr_ext_cost_0 = model.cost_expr_ext_cost - model.cost_expr_ext_cost_custom_hess_0 = model.cost_expr_ext_cost_custom_hess - - model.cost_psi_expr_0 = model.cost_psi_expr - model.cost_r_in_psi_expr_0 = model.cost_r_in_psi_expr - - if cost.cost_type_0 == 'LINEAR_LS': - ny_0 = cost.W_0.shape[0] - if cost.Vx_0.shape[0] != ny_0 or cost.Vu_0.shape[0] != ny_0: - raise Exception('inconsistent dimension ny_0, regarding W_0, Vx_0, Vu_0.' + \ - f'\nGot W_0[{cost.W_0.shape}], Vx_0[{cost.Vx_0.shape}], Vu_0[{cost.Vu_0.shape}]\n') - if dims.nz != 0 and cost.Vz_0.shape[0] != ny_0: - raise Exception('inconsistent dimension ny_0, regarding W_0, Vx_0, Vu_0, Vz_0.' + \ - f'\nGot W_0[{cost.W_0.shape}], Vx_0[{cost.Vx_0.shape}], Vu_0[{cost.Vu_0.shape}], Vz_0[{cost.Vz_0.shape}]\n') - if cost.Vx_0.shape[1] != dims.nx and ny_0 != 0: - raise Exception('inconsistent dimension: Vx_0 should have nx columns.') - if cost.Vu_0.shape[1] != dims.nu and ny_0 != 0: - raise Exception('inconsistent dimension: Vu_0 should have nu columns.') - if cost.yref_0.shape[0] != ny_0: - raise Exception('inconsistent dimension: regarding W_0, yref_0.' + \ - f'\nGot W_0[{cost.W_0.shape}], yref_0[{cost.yref_0.shape}]\n') - dims.ny_0 = ny_0 - - elif cost.cost_type_0 == 'NONLINEAR_LS': - ny_0 = cost.W_0.shape[0] - if is_empty(model.cost_y_expr_0) and ny_0 != 0: - raise Exception('inconsistent dimension ny_0: regarding W_0, cost_y_expr.') - elif casadi_length(model.cost_y_expr_0) != ny_0: - raise Exception('inconsistent dimension ny_0: regarding W_0, cost_y_expr.') - if cost.yref_0.shape[0] != ny_0: - raise Exception('inconsistent dimension: regarding W_0, yref_0.' + \ - f'\nGot W_0[{cost.W.shape}], yref_0[{cost.yref_0.shape}]\n') - dims.ny_0 = ny_0 - - elif cost.cost_type_0 == 'CONVEX_OVER_NONLINEAR': - if is_empty(model.cost_y_expr_0): - raise Exception('cost_y_expr_0 and/or cost_y_expr not provided.') - ny_0 = casadi_length(model.cost_y_expr_0) - if is_empty(model.cost_r_in_psi_expr_0) or casadi_length(model.cost_r_in_psi_expr_0) != ny_0: - raise Exception('inconsistent dimension ny_0: regarding cost_y_expr_0 and cost_r_in_psi_0.') - if is_empty(model.cost_psi_expr_0) or casadi_length(model.cost_psi_expr_0) != 1: - raise Exception('cost_psi_expr_0 not provided or not scalar-valued.') - if cost.yref_0.shape[0] != ny_0: - raise Exception('inconsistent dimension: regarding yref_0 and cost_y_expr_0, cost_r_in_psi_0.') - dims.ny_0 = ny_0 - - if not (opts.hessian_approx=='EXACT' and opts.exact_hess_cost==False) and opts.hessian_approx != 'GAUSS_NEWTON': - raise Exception("\nWith CONVEX_OVER_NONLINEAR cost type, possible Hessian approximations are:\n" - "GAUSS_NEWTON or EXACT with 'exact_hess_cost' == False.\n") - - elif cost.cost_type_0 == 'EXTERNAL': - if opts.hessian_approx == 'GAUSS_NEWTON' and opts.ext_cost_num_hess == 0 and model.cost_expr_ext_cost_custom_hess_0 is None: - print("\nWARNING: Gauss-Newton Hessian approximation with EXTERNAL cost type not possible!\n" - "got cost_type_0: EXTERNAL, hessian_approx: 'GAUSS_NEWTON.'\n" - "GAUSS_NEWTON hessian is only supported for cost_types [NON]LINEAR_LS.\n" - "If you continue, acados will proceed computing the exact hessian for the cost term.\n" - "Note: There is also the option to use the external cost module with a numerical hessian approximation (see `ext_cost_num_hess`).\n" - "OR the option to provide a symbolic custom hessian approximation (see `cost_expr_ext_cost_custom_hess`).\n") - - # path - if cost.cost_type == 'LINEAR_LS': - ny = cost.W.shape[0] - if cost.Vx.shape[0] != ny or cost.Vu.shape[0] != ny: - raise Exception('inconsistent dimension ny, regarding W, Vx, Vu.' + \ - f'\nGot W[{cost.W.shape}], Vx[{cost.Vx.shape}], Vu[{cost.Vu.shape}]\n') - if dims.nz != 0 and cost.Vz.shape[0] != ny: - raise Exception('inconsistent dimension ny, regarding W, Vx, Vu, Vz.' + \ - f'\nGot W[{cost.W.shape}], Vx[{cost.Vx.shape}], Vu[{cost.Vu.shape}], Vz[{cost.Vz.shape}]\n') - if cost.Vx.shape[1] != dims.nx and ny != 0: - raise Exception('inconsistent dimension: Vx should have nx columns.') - if cost.Vu.shape[1] != dims.nu and ny != 0: - raise Exception('inconsistent dimension: Vu should have nu columns.') - if cost.yref.shape[0] != ny: - raise Exception('inconsistent dimension: regarding W, yref.' + \ - f'\nGot W[{cost.W.shape}], yref[{cost.yref.shape}]\n') - dims.ny = ny - - elif cost.cost_type == 'NONLINEAR_LS': - ny = cost.W.shape[0] - if is_empty(model.cost_y_expr) and ny != 0: - raise Exception('inconsistent dimension ny: regarding W, cost_y_expr.') - elif casadi_length(model.cost_y_expr) != ny: - raise Exception('inconsistent dimension ny: regarding W, cost_y_expr.') - if cost.yref.shape[0] != ny: - raise Exception('inconsistent dimension: regarding W, yref.' + \ - f'\nGot W[{cost.W.shape}], yref[{cost.yref.shape}]\n') - dims.ny = ny - - elif cost.cost_type == 'CONVEX_OVER_NONLINEAR': - if is_empty(model.cost_y_expr): - raise Exception('cost_y_expr and/or cost_y_expr not provided.') - ny = casadi_length(model.cost_y_expr) - if is_empty(model.cost_r_in_psi_expr) or casadi_length(model.cost_r_in_psi_expr) != ny: - raise Exception('inconsistent dimension ny: regarding cost_y_expr and cost_r_in_psi.') - if is_empty(model.cost_psi_expr) or casadi_length(model.cost_psi_expr) != 1: - raise Exception('cost_psi_expr not provided or not scalar-valued.') - if cost.yref.shape[0] != ny: - raise Exception('inconsistent dimension: regarding yref and cost_y_expr, cost_r_in_psi.') - dims.ny = ny - - if not (opts.hessian_approx=='EXACT' and opts.exact_hess_cost==False) and opts.hessian_approx != 'GAUSS_NEWTON': - raise Exception("\nWith CONVEX_OVER_NONLINEAR cost type, possible Hessian approximations are:\n" - "GAUSS_NEWTON or EXACT with 'exact_hess_cost' == False.\n") - - - elif cost.cost_type == 'EXTERNAL': - if opts.hessian_approx == 'GAUSS_NEWTON' and opts.ext_cost_num_hess == 0 and model.cost_expr_ext_cost_custom_hess is None: - print("\nWARNING: Gauss-Newton Hessian approximation with EXTERNAL cost type not possible!\n" - "got cost_type: EXTERNAL, hessian_approx: 'GAUSS_NEWTON.'\n" - "GAUSS_NEWTON hessian is only supported for cost_types [NON]LINEAR_LS.\n" - "If you continue, acados will proceed computing the exact hessian for the cost term.\n" - "Note: There is also the option to use the external cost module with a numerical hessian approximation (see `ext_cost_num_hess`).\n" - "OR the option to provide a symbolic custom hessian approximation (see `cost_expr_ext_cost_custom_hess`).\n") - - # terminal - if cost.cost_type_e == 'LINEAR_LS': - ny_e = cost.W_e.shape[0] - if cost.Vx_e.shape[0] != ny_e: - raise Exception('inconsistent dimension ny_e: regarding W_e, cost_y_expr_e.' + \ - f'\nGot W_e[{cost.W_e.shape}], Vx_e[{cost.Vx_e.shape}]') - if cost.Vx_e.shape[1] != dims.nx and ny_e != 0: - raise Exception('inconsistent dimension: Vx_e should have nx columns.') - if cost.yref_e.shape[0] != ny_e: - raise Exception('inconsistent dimension: regarding W_e, yref_e.') - dims.ny_e = ny_e - - elif cost.cost_type_e == 'NONLINEAR_LS': - ny_e = cost.W_e.shape[0] - if is_empty(model.cost_y_expr_e) and ny_e != 0: - raise Exception('inconsistent dimension ny_e: regarding W_e, cost_y_expr_e.') - elif casadi_length(model.cost_y_expr_e) != ny_e: - raise Exception('inconsistent dimension ny_e: regarding W_e, cost_y_expr_e.') - if cost.yref_e.shape[0] != ny_e: - raise Exception('inconsistent dimension: regarding W_e, yref_e.') - dims.ny_e = ny_e - - elif cost.cost_type_e == 'CONVEX_OVER_NONLINEAR': - if is_empty(model.cost_y_expr_e): - raise Exception('cost_y_expr_e not provided.') - ny_e = casadi_length(model.cost_y_expr_e) - if is_empty(model.cost_r_in_psi_expr_e) or casadi_length(model.cost_r_in_psi_expr_e) != ny_e: - raise Exception('inconsistent dimension ny_e: regarding cost_y_expr_e and cost_r_in_psi_e.') - if is_empty(model.cost_psi_expr_e) or casadi_length(model.cost_psi_expr_e) != 1: - raise Exception('cost_psi_expr_e not provided or not scalar-valued.') - if cost.yref_e.shape[0] != ny_e: - raise Exception('inconsistent dimension: regarding yref_e and cost_y_expr_e, cost_r_in_psi_e.') - dims.ny_e = ny_e - - if not (opts.hessian_approx=='EXACT' and opts.exact_hess_cost==False) and opts.hessian_approx != 'GAUSS_NEWTON': - raise Exception("\nWith CONVEX_OVER_NONLINEAR cost type, possible Hessian approximations are:\n" - "GAUSS_NEWTON or EXACT with 'exact_hess_cost' == False.\n") - - - - elif cost.cost_type_e == 'EXTERNAL': - if opts.hessian_approx == 'GAUSS_NEWTON' and opts.ext_cost_num_hess == 0 and model.cost_expr_ext_cost_custom_hess_e is None: - print("\nWARNING: Gauss-Newton Hessian approximation with EXTERNAL cost type not possible!\n" - "got cost_type_e: EXTERNAL, hessian_approx: 'GAUSS_NEWTON.'\n" - "GAUSS_NEWTON hessian is only supported for cost_types [NON]LINEAR_LS.\n" - "If you continue, acados will proceed computing the exact hessian for the cost term.\n" - "Note: There is also the option to use the external cost module with a numerical hessian approximation (see `ext_cost_num_hess`).\n" - "OR the option to provide a symbolic custom hessian approximation (see `cost_expr_ext_cost_custom_hess`).\n") - - ## constraints - # initial - this_shape = constraints.lbx_0.shape - other_shape = constraints.ubx_0.shape - if not this_shape == other_shape: - raise Exception('lbx_0, ubx_0 have different shapes!') - if not is_column(constraints.lbx_0): - raise Exception('lbx_0, ubx_0 must be column vectors!') - dims.nbx_0 = constraints.lbx_0.size - - if all(constraints.lbx_0 == constraints.ubx_0) and dims.nbx_0 == dims.nx \ - and dims.nbxe_0 is None \ - and (constraints.idxbxe_0.shape == constraints.idxbx_0.shape)\ - and all(constraints.idxbxe_0 == constraints.idxbx_0): - # case: x0 was set: nbx0 are all equlities. - dims.nbxe_0 = dims.nbx_0 - elif constraints.idxbxe_0 is not None: - dims.nbxe_0 = constraints.idxbxe_0.shape[0] - elif dims.nbxe_0 is None: - # case: x0 and idxbxe_0 were not set -> dont assume nbx0 to be equality constraints. - dims.nbxe_0 = 0 - - # path - nbx = constraints.idxbx.shape[0] - if constraints.ubx.shape[0] != nbx or constraints.lbx.shape[0] != nbx: - raise Exception('inconsistent dimension nbx, regarding idxbx, ubx, lbx.') - else: - dims.nbx = nbx - - nbu = constraints.idxbu.shape[0] - if constraints.ubu.shape[0] != nbu or constraints.lbu.shape[0] != nbu: - raise Exception('inconsistent dimension nbu, regarding idxbu, ubu, lbu.') - else: - dims.nbu = nbu - - ng = constraints.lg.shape[0] - if constraints.ug.shape[0] != ng or constraints.C.shape[0] != ng \ - or constraints.D.shape[0] != ng: - raise Exception('inconsistent dimension ng, regarding lg, ug, C, D.') - else: - dims.ng = ng - - if not is_empty(model.con_h_expr): - nh = casadi_length(model.con_h_expr) - else: - nh = 0 - - if constraints.uh.shape[0] != nh or constraints.lh.shape[0] != nh: - raise Exception('inconsistent dimension nh, regarding lh, uh, con_h_expr.') - else: - dims.nh = nh - - if is_empty(model.con_phi_expr): - dims.nphi = 0 - dims.nr = 0 - else: - dims.nphi = casadi_length(model.con_phi_expr) - if is_empty(model.con_r_expr): - raise Exception('convex over nonlinear constraints: con_r_expr but con_phi_expr is nonempty') - else: - dims.nr = casadi_length(model.con_r_expr) - - # terminal - nbx_e = constraints.idxbx_e.shape[0] - if constraints.ubx_e.shape[0] != nbx_e or constraints.lbx_e.shape[0] != nbx_e: - raise Exception('inconsistent dimension nbx_e, regarding idxbx_e, ubx_e, lbx_e.') - else: - dims.nbx_e = nbx_e - - ng_e = constraints.lg_e.shape[0] - if constraints.ug_e.shape[0] != ng_e or constraints.C_e.shape[0] != ng_e: - raise Exception('inconsistent dimension ng_e, regarding_e lg_e, ug_e, C_e.') - else: - dims.ng_e = ng_e - - if not is_empty(model.con_h_expr_e): - nh_e = casadi_length(model.con_h_expr_e) - else: - nh_e = 0 - - if constraints.uh_e.shape[0] != nh_e or constraints.lh_e.shape[0] != nh_e: - raise Exception('inconsistent dimension nh_e, regarding lh_e, uh_e, con_h_expr_e.') - else: - dims.nh_e = nh_e - - if is_empty(model.con_phi_expr_e): - dims.nphi_e = 0 - dims.nr_e = 0 - else: - dims.nphi_e = casadi_length(model.con_phi_expr_e) - if is_empty(model.con_r_expr_e): - raise Exception('convex over nonlinear constraints: con_r_expr_e but con_phi_expr_e is nonempty') - else: - dims.nr_e = casadi_length(model.con_r_expr_e) - - # Slack dimensions - nsbx = constraints.idxsbx.shape[0] - if nsbx > nbx: - raise Exception(f'inconsistent dimension nsbx = {nsbx}. Is greater than nbx = {nbx}.') - if is_empty(constraints.lsbx): - constraints.lsbx = np.zeros((nsbx,)) - elif constraints.lsbx.shape[0] != nsbx: - raise Exception('inconsistent dimension nsbx, regarding idxsbx, lsbx.') - if is_empty(constraints.usbx): - constraints.usbx = np.zeros((nsbx,)) - elif constraints.usbx.shape[0] != nsbx: - raise Exception('inconsistent dimension nsbx, regarding idxsbx, usbx.') - dims.nsbx = nsbx - - nsbu = constraints.idxsbu.shape[0] - if nsbu > nbu: - raise Exception(f'inconsistent dimension nsbu = {nsbu}. Is greater than nbu = {nbu}.') - if is_empty(constraints.lsbu): - constraints.lsbu = np.zeros((nsbu,)) - elif constraints.lsbu.shape[0] != nsbu: - raise Exception('inconsistent dimension nsbu, regarding idxsbu, lsbu.') - if is_empty(constraints.usbu): - constraints.usbu = np.zeros((nsbu,)) - elif constraints.usbu.shape[0] != nsbu: - raise Exception('inconsistent dimension nsbu, regarding idxsbu, usbu.') - dims.nsbu = nsbu - - nsh = constraints.idxsh.shape[0] - if nsh > nh: - raise Exception(f'inconsistent dimension nsh = {nsh}. Is greater than nh = {nh}.') - if is_empty(constraints.lsh): - constraints.lsh = np.zeros((nsh,)) - elif constraints.lsh.shape[0] != nsh: - raise Exception('inconsistent dimension nsh, regarding idxsh, lsh.') - if is_empty(constraints.ush): - constraints.ush = np.zeros((nsh,)) - elif constraints.ush.shape[0] != nsh: - raise Exception('inconsistent dimension nsh, regarding idxsh, ush.') - dims.nsh = nsh - - nsphi = constraints.idxsphi.shape[0] - if nsphi > dims.nphi: - raise Exception(f'inconsistent dimension nsphi = {nsphi}. Is greater than nphi = {dims.nphi}.') - if is_empty(constraints.lsphi): - constraints.lsphi = np.zeros((nsphi,)) - elif constraints.lsphi.shape[0] != nsphi: - raise Exception('inconsistent dimension nsphi, regarding idxsphi, lsphi.') - if is_empty(constraints.usphi): - constraints.usphi = np.zeros((nsphi,)) - elif constraints.usphi.shape[0] != nsphi: - raise Exception('inconsistent dimension nsphi, regarding idxsphi, usphi.') - dims.nsphi = nsphi - - nsg = constraints.idxsg.shape[0] - if nsg > ng: - raise Exception(f'inconsistent dimension nsg = {nsg}. Is greater than ng = {ng}.') - if is_empty(constraints.lsg): - constraints.lsg = np.zeros((nsg,)) - elif constraints.lsg.shape[0] != nsg: - raise Exception('inconsistent dimension nsg, regarding idxsg, lsg.') - if is_empty(constraints.usg): - constraints.usg = np.zeros((nsg,)) - elif constraints.usg.shape[0] != nsg: - raise Exception('inconsistent dimension nsg, regarding idxsg, usg.') - dims.nsg = nsg - - ns = nsbx + nsbu + nsh + nsg + nsphi - wrong_field = "" - if cost.Zl.shape[0] != ns: - wrong_field = "Zl" - dim = cost.Zl.shape[0] - elif cost.Zu.shape[0] != ns: - wrong_field = "Zu" - dim = cost.Zu.shape[0] - elif cost.zl.shape[0] != ns: - wrong_field = "zl" - dim = cost.zl.shape[0] - elif cost.zu.shape[0] != ns: - wrong_field = "zu" - dim = cost.zu.shape[0] - - if wrong_field != "": - raise Exception(f'Inconsistent size for field {wrong_field}, with dimension {dim}, \n\t'\ - + f'Detected ns = {ns} = nsbx + nsbu + nsg + nsh + nsphi.\n\t'\ - + f'With nsbx = {nsbx}, nsbu = {nsbu}, nsg = {nsg}, nsh = {nsh}, nsphi = {nsphi}') - - dims.ns = ns - - nsbx_e = constraints.idxsbx_e.shape[0] - if nsbx_e > nbx_e: - raise Exception(f'inconsistent dimension nsbx_e = {nsbx_e}. Is greater than nbx_e = {nbx_e}.') - if is_empty(constraints.lsbx_e): - constraints.lsbx_e = np.zeros((nsbx_e,)) - elif constraints.lsbx_e.shape[0] != nsbx_e: - raise Exception('inconsistent dimension nsbx_e, regarding idxsbx_e, lsbx_e.') - if is_empty(constraints.usbx_e): - constraints.usbx_e = np.zeros((nsbx_e,)) - elif constraints.usbx_e.shape[0] != nsbx_e: - raise Exception('inconsistent dimension nsbx_e, regarding idxsbx_e, usbx_e.') - dims.nsbx_e = nsbx_e - - nsh_e = constraints.idxsh_e.shape[0] - if nsh_e > nh_e: - raise Exception(f'inconsistent dimension nsh_e = {nsh_e}. Is greater than nh_e = {nh_e}.') - if is_empty(constraints.lsh_e): - constraints.lsh_e = np.zeros((nsh_e,)) - elif constraints.lsh_e.shape[0] != nsh_e: - raise Exception('inconsistent dimension nsh_e, regarding idxsh_e, lsh_e.') - if is_empty(constraints.ush_e): - constraints.ush_e = np.zeros((nsh_e,)) - elif constraints.ush_e.shape[0] != nsh_e: - raise Exception('inconsistent dimension nsh_e, regarding idxsh_e, ush_e.') - dims.nsh_e = nsh_e - - nsg_e = constraints.idxsg_e.shape[0] - if nsg_e > ng_e: - raise Exception(f'inconsistent dimension nsg_e = {nsg_e}. Is greater than ng_e = {ng_e}.') - if is_empty(constraints.lsg_e): - constraints.lsg_e = np.zeros((nsg_e,)) - elif constraints.lsg_e.shape[0] != nsg_e: - raise Exception('inconsistent dimension nsg_e, regarding idxsg_e, lsg_e.') - if is_empty(constraints.usg_e): - constraints.usg_e = np.zeros((nsg_e,)) - elif constraints.usg_e.shape[0] != nsg_e: - raise Exception('inconsistent dimension nsg_e, regarding idxsg_e, usg_e.') - dims.nsg_e = nsg_e - - nsphi_e = constraints.idxsphi_e.shape[0] - if nsphi_e > dims.nphi_e: - raise Exception(f'inconsistent dimension nsphi_e = {nsphi_e}. Is greater than nphi_e = {dims.nphi_e}.') - if is_empty(constraints.lsphi_e): - constraints.lsphi_e = np.zeros((nsphi_e,)) - elif constraints.lsphi_e.shape[0] != nsphi_e: - raise Exception('inconsistent dimension nsphi_e, regarding idxsphi_e, lsphi_e.') - if is_empty(constraints.usphi_e): - constraints.usphi_e = np.zeros((nsphi_e,)) - elif constraints.usphi_e.shape[0] != nsphi_e: - raise Exception('inconsistent dimension nsphi_e, regarding idxsphi_e, usphi_e.') - dims.nsphi_e = nsphi_e - - # terminal - ns_e = nsbx_e + nsh_e + nsg_e + nsphi_e - wrong_field = "" - if cost.Zl_e.shape[0] != ns_e: - wrong_field = "Zl_e" - dim = cost.Zl_e.shape[0] - elif cost.Zu_e.shape[0] != ns_e: - wrong_field = "Zu_e" - dim = cost.Zu_e.shape[0] - elif cost.zl_e.shape[0] != ns_e: - wrong_field = "zl_e" - dim = cost.zl_e.shape[0] - elif cost.zu_e.shape[0] != ns_e: - wrong_field = "zu_e" - dim = cost.zu_e.shape[0] - - if wrong_field != "": - raise Exception(f'Inconsistent size for field {wrong_field}, with dimension {dim}, \n\t'\ - + f'Detected ns_e = {ns_e} = nsbx_e + nsg_e + nsh_e + nsphi_e.\n\t'\ - + f'With nsbx_e = {nsbx_e}, nsg_e = {nsg_e}, nsh_e = {nsh_e}, nsphi_e = {nsphi_e}') - - dims.ns_e = ns_e - - # discretization - if is_empty(opts.time_steps) and is_empty(opts.shooting_nodes): - # uniform discretization - opts.time_steps = opts.tf / dims.N * np.ones((dims.N,)) - - elif not is_empty(opts.shooting_nodes): - if np.shape(opts.shooting_nodes)[0] != dims.N+1: - raise Exception('inconsistent dimension N, regarding shooting_nodes.') - - time_steps = opts.shooting_nodes[1:] - opts.shooting_nodes[0:-1] - # identify constant time_steps: due to numerical reasons the content of time_steps might vary a bit - avg_time_steps = np.average(time_steps) - # criterion for constant time step detection: the min/max difference in values normalized by the average - check_const_time_step = (np.max(time_steps)-np.min(time_steps)) / avg_time_steps - # if the criterion is small, we have a constant time_step - if check_const_time_step < 1e-9: - time_steps[:] = avg_time_steps # if we have a constant time_step: apply the average time_step - - opts.time_steps = time_steps - - elif (not is_empty(opts.time_steps)) and (not is_empty(opts.shooting_nodes)): - Exception('Please provide either time_steps or shooting_nodes for nonuniform discretization') - - tf = np.sum(opts.time_steps) - if (tf - opts.tf) / tf > 1e-15: - raise Exception(f'Inconsistent discretization: {opts.tf}'\ - f' = tf != sum(opts.time_steps) = {tf}.') - - # num_steps - if isinstance(opts.sim_method_num_steps, np.ndarray) and opts.sim_method_num_steps.size == 1: - opts.sim_method_num_steps = opts.sim_method_num_steps.item() - - if isinstance(opts.sim_method_num_steps, (int, float)) and opts.sim_method_num_steps % 1 == 0: - opts.sim_method_num_steps = opts.sim_method_num_steps * np.ones((dims.N,), dtype=np.int64) - elif isinstance(opts.sim_method_num_steps, np.ndarray) and opts.sim_method_num_steps.size == dims.N \ - and np.all(np.equal(np.mod(opts.sim_method_num_steps, 1), 0)): - opts.sim_method_num_steps = np.reshape(opts.sim_method_num_steps, (dims.N,)).astype(np.int64) - else: - raise Exception("Wrong value for sim_method_num_steps. Should be either int or array of ints of shape (N,).") - - # num_stages - if isinstance(opts.sim_method_num_stages, np.ndarray) and opts.sim_method_num_stages.size == 1: - opts.sim_method_num_stages = opts.sim_method_num_stages.item() - - if isinstance(opts.sim_method_num_stages, (int, float)) and opts.sim_method_num_stages % 1 == 0: - opts.sim_method_num_stages = opts.sim_method_num_stages * np.ones((dims.N,), dtype=np.int64) - elif isinstance(opts.sim_method_num_stages, np.ndarray) and opts.sim_method_num_stages.size == dims.N \ - and np.all(np.equal(np.mod(opts.sim_method_num_stages, 1), 0)): - opts.sim_method_num_stages = np.reshape(opts.sim_method_num_stages, (dims.N,)).astype(np.int64) - else: - raise Exception("Wrong value for sim_method_num_stages. Should be either int or array of ints of shape (N,).") - - # jac_reuse - if isinstance(opts.sim_method_jac_reuse, np.ndarray) and opts.sim_method_jac_reuse.size == 1: - opts.sim_method_jac_reuse = opts.sim_method_jac_reuse.item() - - if isinstance(opts.sim_method_jac_reuse, (int, float)) and opts.sim_method_jac_reuse % 1 == 0: - opts.sim_method_jac_reuse = opts.sim_method_jac_reuse * np.ones((dims.N,), dtype=np.int64) - elif isinstance(opts.sim_method_jac_reuse, np.ndarray) and opts.sim_method_jac_reuse.size == dims.N \ - and np.all(np.equal(np.mod(opts.sim_method_jac_reuse, 1), 0)): - opts.sim_method_jac_reuse = np.reshape(opts.sim_method_jac_reuse, (dims.N,)).astype(np.int64) - else: - raise Exception("Wrong value for sim_method_jac_reuse. Should be either int or array of ints of shape (N,).") - - -def get_simulink_default_opts(): - python_interface_path = get_python_interface_path() - abs_path = os.path.join(python_interface_path, 'simulink_default_opts.json') - with open(abs_path , 'r') as f: - simulink_default_opts = json.load(f) - return simulink_default_opts - - -def ocp_formulation_json_dump(acados_ocp, simulink_opts=None, json_file='acados_ocp_nlp.json'): - # Load acados_ocp_nlp structure description - ocp_layout = get_ocp_nlp_layout() - - # Copy input ocp object dictionary - ocp_nlp_dict = dict(deepcopy(acados_ocp).__dict__) - # TODO: maybe make one function with formatting - - for acados_struct, v in ocp_layout.items(): - # skip non dict attributes - if not isinstance(v, dict): - continue - # setattr(ocp_nlp, acados_struct, dict(getattr(acados_ocp, acados_struct).__dict__)) - # Copy ocp object attributes dictionaries - ocp_nlp_dict[acados_struct]=dict(getattr(acados_ocp, acados_struct).__dict__) - - ocp_nlp_dict = format_class_dict(ocp_nlp_dict) - - if simulink_opts is not None: - ocp_nlp_dict['simulink_opts'] = simulink_opts - - with open(json_file, 'w') as f: - json.dump(ocp_nlp_dict, f, default=make_object_json_dumpable, indent=4, sort_keys=True) - - - -def ocp_formulation_json_load(json_file='acados_ocp_nlp.json'): - # Load acados_ocp_nlp structure description - ocp_layout = get_ocp_nlp_layout() - - with open(json_file, 'r') as f: - ocp_nlp_json = json.load(f) - - ocp_nlp_dict = json2dict(ocp_nlp_json, ocp_nlp_json['dims']) - - # Instantiate AcadosOcp object - acados_ocp = AcadosOcp() - - # load class dict - acados_ocp.__dict__ = ocp_nlp_dict - - # load class attributes dict, dims, constraints, etc - for acados_struct, v in ocp_layout.items(): - # skip non dict attributes - if not isinstance(v, dict): - continue - acados_attribute = getattr(acados_ocp, acados_struct) - acados_attribute.__dict__ = ocp_nlp_dict[acados_struct] - setattr(acados_ocp, acados_struct, acados_attribute) - - return acados_ocp - - -def ocp_generate_external_functions(acados_ocp: AcadosOcp, model: AcadosModel): - - model = make_model_consistent(model) - - if acados_ocp.solver_options.hessian_approx == 'EXACT': - opts = dict(generate_hess=1) - else: - opts = dict(generate_hess=0) - - # create code_export_dir, model_dir - code_export_dir = acados_ocp.code_export_directory - opts['code_export_directory'] = code_export_dir - model_dir = os.path.join(code_export_dir, model.name + '_model') - if not os.path.exists(model_dir): - os.makedirs(model_dir) - - check_casadi_version() - # TODO: remove dir gen from all the generate_c_* functions - if acados_ocp.model.dyn_ext_fun_type == 'casadi': - if acados_ocp.solver_options.integrator_type == 'ERK': - generate_c_code_explicit_ode(model, opts) - elif acados_ocp.solver_options.integrator_type == 'IRK': - generate_c_code_implicit_ode(model, opts) - elif acados_ocp.solver_options.integrator_type == 'LIFTED_IRK': - generate_c_code_implicit_ode(model, opts) - elif acados_ocp.solver_options.integrator_type == 'GNSF': - generate_c_code_gnsf(model, opts) - elif acados_ocp.solver_options.integrator_type == 'DISCRETE': - generate_c_code_discrete_dynamics(model, opts) - else: - raise Exception("ocp_generate_external_functions: unknown integrator type.") - else: - target_location = os.path.join(code_export_dir, model_dir, model.dyn_generic_source) - shutil.copyfile(model.dyn_generic_source, target_location) - - if acados_ocp.dims.nphi > 0 or acados_ocp.dims.nh > 0: - generate_c_code_constraint(model, model.name, False, opts) - - if acados_ocp.dims.nphi_e > 0 or acados_ocp.dims.nh_e > 0: - generate_c_code_constraint(model, model.name, True, opts) - - if acados_ocp.cost.cost_type_0 == 'NONLINEAR_LS': - generate_c_code_nls_cost(model, model.name, 'initial', opts) - elif acados_ocp.cost.cost_type_0 == 'CONVEX_OVER_NONLINEAR': - generate_c_code_conl_cost(model, model.name, 'initial', opts) - elif acados_ocp.cost.cost_type_0 == 'EXTERNAL': - generate_c_code_external_cost(model, 'initial', opts) - - if acados_ocp.cost.cost_type == 'NONLINEAR_LS': - generate_c_code_nls_cost(model, model.name, 'path', opts) - elif acados_ocp.cost.cost_type == 'CONVEX_OVER_NONLINEAR': - generate_c_code_conl_cost(model, model.name, 'path', opts) - elif acados_ocp.cost.cost_type == 'EXTERNAL': - generate_c_code_external_cost(model, 'path', opts) - - if acados_ocp.cost.cost_type_e == 'NONLINEAR_LS': - generate_c_code_nls_cost(model, model.name, 'terminal', opts) - elif acados_ocp.cost.cost_type_e == 'CONVEX_OVER_NONLINEAR': - generate_c_code_conl_cost(model, model.name, 'terminal', opts) - elif acados_ocp.cost.cost_type_e == 'EXTERNAL': - generate_c_code_external_cost(model, 'terminal', opts) - - -def ocp_get_default_cmake_builder() -> CMakeBuilder: - """ - If :py:class:`~acados_template.acados_ocp_solver.AcadosOcpSolver` is used with `CMake` this function returns a good first setting. - :return: default :py:class:`~acados_template.builders.CMakeBuilder` - """ - cmake_builder = CMakeBuilder() - cmake_builder.options_on = ['BUILD_ACADOS_OCP_SOLVER_LIB'] - return cmake_builder - - - -def ocp_render_templates(acados_ocp: AcadosOcp, json_file, cmake_builder=None, simulink_opts=None): - - # setting up loader and environment - json_path = os.path.abspath(json_file) - - if not os.path.exists(json_path): - raise Exception(f'Path "{json_path}" not found!') - - # Render templates - template_list = __ocp_get_template_list(acados_ocp, cmake_builder=cmake_builder, simulink_opts=simulink_opts) - for tup in template_list: - if len(tup) > 2: - output_dir = tup[2] - else: - output_dir = acados_ocp.code_export_directory - render_template(tup[0], tup[1], output_dir, json_path) - - # Custom templates - acados_template_path = os.path.dirname(os.path.abspath(__file__)) - custom_template_glob = os.path.join(acados_template_path, 'custom_update_templates', '*') - for tup in acados_ocp.solver_options.custom_templates: - render_template(tup[0], tup[1], acados_ocp.code_export_directory, json_path, template_glob=custom_template_glob) - - return - - - -def __ocp_get_template_list(acados_ocp: AcadosOcp, cmake_builder=None, simulink_opts=None) -> list: - """ - returns a list of tuples in the form: - (input_filename, output_filname) - or - (input_filename, output_filname, output_directory) - """ - name = acados_ocp.model.name - code_export_directory = acados_ocp.code_export_directory - template_list = [] - - template_list.append(('main.in.c', f'main_{name}.c')) - template_list.append(('acados_solver.in.c', f'acados_solver_{name}.c')) - template_list.append(('acados_solver.in.h', f'acados_solver_{name}.h')) - template_list.append(('acados_solver.in.pxd', f'acados_solver.pxd')) - if cmake_builder is not None: - template_list.append(('CMakeLists.in.txt', 'CMakeLists.txt')) - else: - template_list.append(('Makefile.in', 'Makefile')) - - - # sim - template_list.append(('acados_sim_solver.in.c', f'acados_sim_solver_{name}.c')) - template_list.append(('acados_sim_solver.in.h', f'acados_sim_solver_{name}.h')) - template_list.append(('main_sim.in.c', f'main_sim_{name}.c')) - - # model - model_dir = os.path.join(code_export_directory, f'{name}_model') - template_list.append(('model.in.h', f'{name}_model.h', model_dir)) - # constraints - constraints_dir = os.path.join(code_export_directory, f'{name}_constraints') - template_list.append(('constraints.in.h', f'{name}_constraints.h', constraints_dir)) - # cost - cost_dir = os.path.join(code_export_directory, f'{name}_cost') - template_list.append(('cost.in.h', f'{name}_cost.h', cost_dir)) - - # Simulink - if simulink_opts is not None: - template_file = os.path.join('matlab_templates', 'acados_solver_sfun.in.c') - template_list.append((template_file, f'acados_solver_sfunction_{name}.c')) - template_file = os.path.join('matlab_templates', 'acados_solver_sfun.in.c') - template_list.append((template_file, f'make_sfun_{name}.m')) - - return template_list - - -def remove_x0_elimination(acados_ocp): - acados_ocp.constraints.idxbxe_0 = np.zeros((0,)) - acados_ocp.dims.nbxe_0 = 0 - - -class AcadosOcpSolver: - """ - Class to interact with the acados ocp solver C object. - - :param acados_ocp: type :py:class:`~acados_template.acados_ocp.AcadosOcp` - description of the OCP for acados - :param json_file: name for the json file used to render the templated code - default: acados_ocp_nlp.json - :param simulink_opts: Options to configure Simulink S-function blocks, mainly to activate possible Inputs and Outputs - """ - if sys.platform=="win32": - from ctypes import wintypes - from ctypes import WinDLL - dlclose = WinDLL('kernel32', use_last_error=True).FreeLibrary - dlclose.argtypes = [wintypes.HMODULE] - else: - dlclose = CDLL(None).dlclose - dlclose.argtypes = [c_void_p] - - @classmethod - def generate(cls, acados_ocp: AcadosOcp, json_file='acados_ocp_nlp.json', simulink_opts=None, cmake_builder: CMakeBuilder = None): - """ - Generates the code for an acados OCP solver, given the description in acados_ocp. - :param acados_ocp: type AcadosOcp - description of the OCP for acados - :param json_file: name for the json file used to render the templated code - default: `acados_ocp_nlp.json` - :param simulink_opts: Options to configure Simulink S-function blocks, mainly to activate possible inputs and - outputs; default: `None` - :param cmake_builder: type :py:class:`~acados_template.builders.CMakeBuilder` generate a `CMakeLists.txt` and use - the `CMake` pipeline instead of a `Makefile` (`CMake` seems to be the better option in conjunction with - `MS Visual Studio`); default: `None` - """ - model = acados_ocp.model - acados_ocp.code_export_directory = os.path.abspath(acados_ocp.code_export_directory) - - # make dims consistent - make_ocp_dims_consistent(acados_ocp) - - # module dependent post processing - if acados_ocp.solver_options.integrator_type == 'GNSF': - if 'gnsf_model' in acados_ocp.__dict__: - set_up_imported_gnsf_model(acados_ocp) - else: - detect_gnsf_structure(acados_ocp) - - if acados_ocp.solver_options.qp_solver == 'PARTIAL_CONDENSING_QPDUNES': - remove_x0_elimination(acados_ocp) - - # set integrator time automatically - acados_ocp.solver_options.Tsim = acados_ocp.solver_options.time_steps[0] - - # generate external functions - ocp_generate_external_functions(acados_ocp, model) - - # dump to json - acados_ocp.json_file = json_file - ocp_formulation_json_dump(acados_ocp, simulink_opts=simulink_opts, json_file=json_file) - - # render templates - ocp_render_templates(acados_ocp, json_file, cmake_builder=cmake_builder, simulink_opts=simulink_opts) - - # copy custom update function - if acados_ocp.solver_options.custom_update_filename != "" and acados_ocp.solver_options.custom_update_copy: - target_location = os.path.join(acados_ocp.code_export_directory, acados_ocp.solver_options.custom_update_filename) - shutil.copyfile(acados_ocp.solver_options.custom_update_filename, target_location) - if acados_ocp.solver_options.custom_update_header_filename != "" and acados_ocp.solver_options.custom_update_copy: - target_location = os.path.join(acados_ocp.code_export_directory, acados_ocp.solver_options.custom_update_header_filename) - shutil.copyfile(acados_ocp.solver_options.custom_update_header_filename, target_location) - - - @classmethod - def build(cls, code_export_dir, with_cython=False, cmake_builder: CMakeBuilder = None, verbose: bool = True): - """ - Builds the code for an acados OCP solver, that has been generated in code_export_dir - :param code_export_dir: directory in which acados OCP solver has been generated, see generate() - :param with_cython: option indicating if the cython interface is build, default: False. - :param cmake_builder: type :py:class:`~acados_template.builders.CMakeBuilder` generate a `CMakeLists.txt` and use - the `CMake` pipeline instead of a `Makefile` (`CMake` seems to be the better option in conjunction with - `MS Visual Studio`); default: `None` - :param verbose: indicating if build command is printed - """ - code_export_dir = os.path.abspath(code_export_dir) - cwd = os.getcwd() - os.chdir(code_export_dir) - if with_cython: - call( - ['make', 'clean_all'], - stdout=None if verbose else DEVNULL, - stderr=None if verbose else STDOUT - ) - call( - ['make', 'ocp_cython'], - stdout=None if verbose else DEVNULL, - stderr=None if verbose else STDOUT - ) - else: - if cmake_builder is not None: - cmake_builder.exec(code_export_dir) - else: - call( - ['make', 'clean_ocp_shared_lib'], - stdout=None if verbose else DEVNULL, - stderr=None if verbose else STDOUT - ) - call( - ['make', 'ocp_shared_lib'], - stdout=None if verbose else DEVNULL, - stderr=None if verbose else STDOUT - ) - os.chdir(cwd) - - - @classmethod - def create_cython_solver(cls, json_file): - """ - Returns an `AcadosOcpSolverCython` object. - - This is an alternative Cython based Python wrapper to the acados OCP solver in C. - This offers faster interaction with the solver, because getter and setter calls, which include shape checking are done in compiled C code. - - The default wrapper `AcadosOcpSolver` is based on ctypes. - """ - with open(json_file, 'r') as f: - acados_ocp_json = json.load(f) - code_export_directory = acados_ocp_json['code_export_directory'] - - importlib.invalidate_caches() - rel_code_export_directory = os.path.relpath(code_export_directory) - acados_ocp_solver_pyx = importlib.import_module(f'{rel_code_export_directory}.acados_ocp_solver_pyx') - - AcadosOcpSolverCython = getattr(acados_ocp_solver_pyx, 'AcadosOcpSolverCython') - return AcadosOcpSolverCython(acados_ocp_json['model']['name'], - acados_ocp_json['solver_options']['nlp_solver_type'], - acados_ocp_json['dims']['N']) - - - def __init__(self, acados_ocp: AcadosOcp, json_file='acados_ocp_nlp.json', simulink_opts=None, build=True, generate=True, cmake_builder: CMakeBuilder = None, verbose=True): - - self.solver_created = False - if generate: - self.generate(acados_ocp, json_file=json_file, simulink_opts=simulink_opts, cmake_builder=cmake_builder) - - # load json, store options in object - with open(json_file, 'r') as f: - acados_ocp_json = json.load(f) - self.N = acados_ocp_json['dims']['N'] - self.model_name = acados_ocp_json['model']['name'] - self.solver_options = acados_ocp_json['solver_options'] - - acados_lib_path = acados_ocp_json['acados_lib_path'] - code_export_directory = acados_ocp_json['code_export_directory'] - - if build: - self.build(code_export_directory, with_cython=False, cmake_builder=cmake_builder, verbose=verbose) - - # prepare library loading - lib_prefix = 'lib' - lib_ext = get_lib_ext() - if os.name == 'nt': - lib_prefix = '' - - # Load acados library to avoid unloading the library. - # This is necessary if acados was compiled with OpenMP, since the OpenMP threads can't be destroyed. - # Unloading a library which uses OpenMP results in a segfault (on any platform?). - # see [https://stackoverflow.com/questions/34439956/vc-crash-when-freeing-a-dll-built-with-openmp] - # or [https://python.hotexamples.com/examples/_ctypes/-/dlclose/python-dlclose-function-examples.html] - libacados_name = f'{lib_prefix}acados{lib_ext}' - libacados_filepath = os.path.join(acados_lib_path, libacados_name) - self.__acados_lib = CDLL(libacados_filepath) - # find out if acados was compiled with OpenMP - try: - self.__acados_lib_uses_omp = getattr(self.__acados_lib, 'omp_get_thread_num') is not None - except AttributeError as e: - self.__acados_lib_uses_omp = False - if self.__acados_lib_uses_omp: - print('acados was compiled with OpenMP.') - else: - print('acados was compiled without OpenMP.') - libacados_ocp_solver_name = f'{lib_prefix}acados_ocp_solver_{self.model_name}{lib_ext}' - self.shared_lib_name = os.path.join(code_export_directory, libacados_ocp_solver_name) - - # get shared_lib - self.shared_lib = CDLL(self.shared_lib_name) - - # create capsule - getattr(self.shared_lib, f"{self.model_name}_acados_create_capsule").restype = c_void_p - self.capsule = getattr(self.shared_lib, f"{self.model_name}_acados_create_capsule")() - - # create solver - getattr(self.shared_lib, f"{self.model_name}_acados_create").argtypes = [c_void_p] - getattr(self.shared_lib, f"{self.model_name}_acados_create").restype = c_int - assert getattr(self.shared_lib, f"{self.model_name}_acados_create")(self.capsule)==0 - self.solver_created = True - - self.acados_ocp = acados_ocp - - # get pointers solver - self.__get_pointers_solver() - - self.status = 0 - - # gettable fields - self.__qp_dynamics_fields = ['A', 'B', 'b'] - self.__qp_cost_fields = ['Q', 'R', 'S', 'q', 'r'] - self.__qp_constraint_fields = ['C', 'D', 'lg', 'ug', 'lbx', 'ubx', 'lbu', 'ubu'] - - - def __get_pointers_solver(self): - # """ - # Private function to get the pointers for solver - # """ - # get pointers solver - getattr(self.shared_lib, f"{self.model_name}_acados_get_nlp_opts").argtypes = [c_void_p] - getattr(self.shared_lib, f"{self.model_name}_acados_get_nlp_opts").restype = c_void_p - self.nlp_opts = getattr(self.shared_lib, f"{self.model_name}_acados_get_nlp_opts")(self.capsule) - - getattr(self.shared_lib, f"{self.model_name}_acados_get_nlp_dims").argtypes = [c_void_p] - getattr(self.shared_lib, f"{self.model_name}_acados_get_nlp_dims").restype = c_void_p - self.nlp_dims = getattr(self.shared_lib, f"{self.model_name}_acados_get_nlp_dims")(self.capsule) - - getattr(self.shared_lib, f"{self.model_name}_acados_get_nlp_config").argtypes = [c_void_p] - getattr(self.shared_lib, f"{self.model_name}_acados_get_nlp_config").restype = c_void_p - self.nlp_config = getattr(self.shared_lib, f"{self.model_name}_acados_get_nlp_config")(self.capsule) - - getattr(self.shared_lib, f"{self.model_name}_acados_get_nlp_out").argtypes = [c_void_p] - getattr(self.shared_lib, f"{self.model_name}_acados_get_nlp_out").restype = c_void_p - self.nlp_out = getattr(self.shared_lib, f"{self.model_name}_acados_get_nlp_out")(self.capsule) - - getattr(self.shared_lib, f"{self.model_name}_acados_get_sens_out").argtypes = [c_void_p] - getattr(self.shared_lib, f"{self.model_name}_acados_get_sens_out").restype = c_void_p - self.sens_out = getattr(self.shared_lib, f"{self.model_name}_acados_get_sens_out")(self.capsule) - - getattr(self.shared_lib, f"{self.model_name}_acados_get_nlp_in").argtypes = [c_void_p] - getattr(self.shared_lib, f"{self.model_name}_acados_get_nlp_in").restype = c_void_p - self.nlp_in = getattr(self.shared_lib, f"{self.model_name}_acados_get_nlp_in")(self.capsule) - - getattr(self.shared_lib, f"{self.model_name}_acados_get_nlp_solver").argtypes = [c_void_p] - getattr(self.shared_lib, f"{self.model_name}_acados_get_nlp_solver").restype = c_void_p - self.nlp_solver = getattr(self.shared_lib, f"{self.model_name}_acados_get_nlp_solver")(self.capsule) - - - - def solve_for_x0(self, x0_bar): - """ - Wrapper around `solve()` which sets initial state constraint, solves the OCP, and returns u0. - """ - self.set(0, "lbx", x0_bar) - self.set(0, "ubx", x0_bar) - - status = self.solve() - - if status == 2: - print("Warning: acados_ocp_solver reached maximum iterations.") - elif status != 0: - raise Exception(f'acados acados_ocp_solver returned status {status}') - - u0 = self.get(0, "u") - return u0 - - - def solve(self): - """ - Solve the ocp with current input. - """ - getattr(self.shared_lib, f"{self.model_name}_acados_solve").argtypes = [c_void_p] - getattr(self.shared_lib, f"{self.model_name}_acados_solve").restype = c_int - self.status = getattr(self.shared_lib, f"{self.model_name}_acados_solve")(self.capsule) - - return self.status - - - def custom_update(self, data_: np.ndarray): - """ - A custom function that can be implemented by a user to be called between solver calls. - By default this does nothing. - The idea is to have a convenient wrapper to do complex updates of parameters and numerical data efficiently in C, - in a function that is compiled into the solver library and can be conveniently used in the Python environment. - """ - data = np.ascontiguousarray(data_, dtype=np.float64) - c_data = cast(data.ctypes.data, POINTER(c_double)) - data_len = len(data) - - getattr(self.shared_lib, f"{self.model_name}_acados_custom_update").argtypes = [c_void_p, POINTER(c_double), c_int] - getattr(self.shared_lib, f"{self.model_name}_acados_custom_update").restype = c_int - status = getattr(self.shared_lib, f"{self.model_name}_acados_custom_update")(self.capsule, c_data, data_len) - - return status - - - def reset(self, reset_qp_solver_mem=1): - """ - Sets current iterate to all zeros. - """ - getattr(self.shared_lib, f"{self.model_name}_acados_reset").argtypes = [c_void_p, c_int] - getattr(self.shared_lib, f"{self.model_name}_acados_reset").restype = c_int - getattr(self.shared_lib, f"{self.model_name}_acados_reset")(self.capsule, reset_qp_solver_mem) - - return - - - def set_new_time_steps(self, new_time_steps): - """ - Set new time steps. - Recreates the solver if N changes. - - :param new_time_steps: 1 dimensional np array of new time steps for the solver - - .. note:: This allows for different use-cases: either set a new size of time_steps or a new distribution of - the shooting nodes without changing the number, e.g., to reach a different final time. Both cases - do not require a new code export and compilation. - """ - - # unlikely but still possible - if not self.solver_created: - raise Exception('Solver was not yet created!') - - # check if time steps really changed in value - if np.array_equal(self.solver_options['time_steps'], new_time_steps): - return - - N = new_time_steps.size - new_time_steps_data = cast(new_time_steps.ctypes.data, POINTER(c_double)) - - # check if recreation of acados is necessary (no need to recreate acados if sizes are identical) - if len(self.solver_options['time_steps']) == N: - getattr(self.shared_lib, f"{self.model_name}_acados_update_time_steps").argtypes = [c_void_p, c_int, c_void_p] - getattr(self.shared_lib, f"{self.model_name}_acados_update_time_steps").restype = c_int - assert getattr(self.shared_lib, f"{self.model_name}_acados_update_time_steps")(self.capsule, N, new_time_steps_data) == 0 - else: # recreate the solver with the new time steps - self.solver_created = False - - # delete old memory (analog to __del__) - getattr(self.shared_lib, f"{self.model_name}_acados_free").argtypes = [c_void_p] - getattr(self.shared_lib, f"{self.model_name}_acados_free").restype = c_int - getattr(self.shared_lib, f"{self.model_name}_acados_free")(self.capsule) - - # create solver with new time steps - getattr(self.shared_lib, f"{self.model_name}_acados_create_with_discretization").argtypes = [c_void_p, c_int, c_void_p] - getattr(self.shared_lib, f"{self.model_name}_acados_create_with_discretization").restype = c_int - assert getattr(self.shared_lib, f"{self.model_name}_acados_create_with_discretization")(self.capsule, N, new_time_steps_data) == 0 - - self.solver_created = True - - # get pointers solver - self.__get_pointers_solver() - - # store time_steps, N - self.solver_options['time_steps'] = new_time_steps - self.N = N - self.solver_options['Tsim'] = self.solver_options['time_steps'][0] - - - def update_qp_solver_cond_N(self, qp_solver_cond_N: int): - """ - Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver. - This function is relevant for code reuse, i.e., if either `set_new_time_steps(...)` is used or - the influence of a different `qp_solver_cond_N` is studied without code export and compilation. - :param qp_solver_cond_N: new number of condensing stages for the solver - - .. note:: This function can only be used in combination with a partial condensing QP solver. - - .. note:: After `set_new_time_steps(...)` is used and depending on the new number of time steps it might be - necessary to change `qp_solver_cond_N` as well (using this function), i.e., typically - `qp_solver_cond_N < N`. - """ - # unlikely but still possible - if not self.solver_created: - raise Exception('Solver was not yet created!') - if self.N < qp_solver_cond_N: - raise Exception('Setting qp_solver_cond_N to be larger than N does not work!') - if self.solver_options['qp_solver_cond_N'] != qp_solver_cond_N: - self.solver_created = False - - # recreate the solver - fun_name = f'{self.model_name}_acados_update_qp_solver_cond_N' - getattr(self.shared_lib, fun_name).argtypes = [c_void_p, c_int] - getattr(self.shared_lib, fun_name).restype = c_int - assert getattr(self.shared_lib, fun_name)(self.capsule, qp_solver_cond_N) == 0 - - # store the new value - self.solver_options['qp_solver_cond_N'] = qp_solver_cond_N - self.solver_created = True - - # get pointers solver - self.__get_pointers_solver() - - - def eval_param_sens(self, index, stage=0, field="ex"): - """ - Calculate the sensitivity of the curent solution with respect to the initial state component of index - - :param index: integer corresponding to initial state index in range(nx) - """ - - field_ = field - field = field_.encode('utf-8') - - # checks - if not isinstance(index, int): - raise Exception('AcadosOcpSolver.eval_param_sens(): index must be Integer.') - - self.shared_lib.ocp_nlp_dims_get_from_attr.argtypes = [c_void_p, c_void_p, c_void_p, c_int, c_char_p] - self.shared_lib.ocp_nlp_dims_get_from_attr.restype = c_int - nx = self.shared_lib.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) - - if index < 0 or index > nx: - raise Exception(f'AcadosOcpSolver.eval_param_sens(): index must be in [0, nx-1], got: {index}.') - - # actual eval_param - self.shared_lib.ocp_nlp_eval_param_sens.argtypes = [c_void_p, c_char_p, c_int, c_int, c_void_p] - self.shared_lib.ocp_nlp_eval_param_sens.restype = None - self.shared_lib.ocp_nlp_eval_param_sens(self.nlp_solver, field, stage, index, self.sens_out) - - return - - - def get(self, stage_, field_): - """ - Get the last solution of the solver: - - :param stage: integer corresponding to shooting node - :param field: string in ['x', 'u', 'z', 'pi', 'lam', 't', 'sl', 'su',] - - .. note:: regarding lam, t: \n - the inequalities are internally organized in the following order: \n - [ lbu lbx lg lh lphi ubu ubx ug uh uphi; \n - lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi] - - .. note:: pi: multipliers for dynamics equality constraints \n - lam: multipliers for inequalities \n - t: slack variables corresponding to evaluation of all inequalities (at the solution) \n - sl: slack variables of soft lower inequality constraints \n - su: slack variables of soft upper inequality constraints \n - """ - - out_fields = ['x', 'u', 'z', 'pi', 'lam', 't', 'sl', 'su'] - # mem_fields = ['sl', 'su'] - sens_fields = ['sens_u', "sens_x"] - all_fields = out_fields + sens_fields - - field = field_ - - if (field_ not in all_fields): - raise Exception(f'AcadosOcpSolver.get(stage={stage_}, field={field_}): \'{field_}\' is an invalid argument.\ - \n Possible values are {all_fields}.') - - if not isinstance(stage_, int): - raise Exception(f'AcadosOcpSolver.get(stage={stage_}, field={field_}): stage index must be an integer, got type {type(stage_)}.') - - if stage_ < 0 or stage_ > self.N: - raise Exception(f'AcadosOcpSolver.get(stage={stage_}, field={field_}): stage index must be in [0, {self.N}], got: {stage_}.') - - if stage_ == self.N and field_ == 'pi': - raise Exception(f'AcadosOcpSolver.get(stage={stage_}, field={field_}): field \'{field_}\' does not exist at final stage {stage_}.') - - if field_ in sens_fields: - field = field_.replace('sens_', '') - - field = field.encode('utf-8') - - self.shared_lib.ocp_nlp_dims_get_from_attr.argtypes = \ - [c_void_p, c_void_p, c_void_p, c_int, c_char_p] - self.shared_lib.ocp_nlp_dims_get_from_attr.restype = c_int - - dims = self.shared_lib.ocp_nlp_dims_get_from_attr(self.nlp_config, \ - self.nlp_dims, self.nlp_out, stage_, field) - - out = np.ascontiguousarray(np.zeros((dims,)), dtype=np.float64) - out_data = cast(out.ctypes.data, POINTER(c_double)) - - if (field_ in out_fields): - self.shared_lib.ocp_nlp_out_get.argtypes = \ - [c_void_p, c_void_p, c_void_p, c_int, c_char_p, c_void_p] - self.shared_lib.ocp_nlp_out_get(self.nlp_config, \ - self.nlp_dims, self.nlp_out, stage_, field, out_data) - # elif field_ in mem_fields: - # self.shared_lib.ocp_nlp_get_at_stage.argtypes = \ - # [c_void_p, c_void_p, c_void_p, c_int, c_char_p, c_void_p] - # self.shared_lib.ocp_nlp_get_at_stage(self.nlp_config, \ - # self.nlp_dims, self.nlp_solver, stage_, field, out_data) - elif field_ in sens_fields: - self.shared_lib.ocp_nlp_out_get.argtypes = \ - [c_void_p, c_void_p, c_void_p, c_int, c_char_p, c_void_p] - self.shared_lib.ocp_nlp_out_get(self.nlp_config, \ - self.nlp_dims, self.sens_out, stage_, field, out_data) - - return out - - - def print_statistics(self): - """ - prints statistics of previous solver run as a table: - - iter: iteration number - - res_stat: stationarity residual - - res_eq: residual wrt equality constraints (dynamics) - - res_ineq: residual wrt inequality constraints (constraints) - - res_comp: residual wrt complementarity conditions - - qp_stat: status of QP solver - - qp_iter: number of QP iterations - - alpha: SQP step size - - qp_res_stat: stationarity residual of the last QP solution - - qp_res_eq: residual wrt equality constraints (dynamics) of the last QP solution - - qp_res_ineq: residual wrt inequality constraints (constraints) of the last QP solution - - qp_res_comp: residual wrt complementarity conditions of the last QP solution - """ - stat = self.get_stats("statistics") - - if self.solver_options['nlp_solver_type'] == 'SQP': - print('\niter\tres_stat\tres_eq\t\tres_ineq\tres_comp\tqp_stat\tqp_iter\talpha') - if stat.shape[0]>8: - print('\tqp_res_stat\tqp_res_eq\tqp_res_ineq\tqp_res_comp') - for jj in range(stat.shape[1]): - print(f'{int(stat[0][jj]):d}\t{stat[1][jj]:e}\t{stat[2][jj]:e}\t{stat[3][jj]:e}\t' + - f'{stat[4][jj]:e}\t{int(stat[5][jj]):d}\t{int(stat[6][jj]):d}\t{stat[7][jj]:e}\t') - if stat.shape[0]>8: - print('\t{:e}\t{:e}\t{:e}\t{:e}'.format( \ - stat[8][jj], stat[9][jj], stat[10][jj], stat[11][jj])) - print('\n') - elif self.solver_options['nlp_solver_type'] == 'SQP_RTI': - print('\niter\tqp_stat\tqp_iter') - if stat.shape[0]>3: - print('\tqp_res_stat\tqp_res_eq\tqp_res_ineq\tqp_res_comp') - for jj in range(stat.shape[1]): - print('{:d}\t{:d}\t{:d}'.format( int(stat[0][jj]), int(stat[1][jj]), int(stat[2][jj]))) - if stat.shape[0]>3: - print('\t{:e}\t{:e}\t{:e}\t{:e}'.format( \ - stat[3][jj], stat[4][jj], stat[5][jj], stat[6][jj])) - print('\n') - - return - - - def store_iterate(self, filename: str = '', overwrite=False): - """ - Stores the current iterate of the ocp solver in a json file. - - :param filename: if not set, use f'{self.model_name}_iterate.json' - :param overwrite: if false and filename exists add timestamp to filename - """ - if filename == '': - filename = f'{self.model_name}_iterate.json' - - if not overwrite: - # append timestamp - if os.path.isfile(filename): - filename = filename[:-5] - filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' - - # get iterate: - solution = dict() - - lN = len(str(self.N+1)) - for i in range(self.N+1): - i_string = f'{i:0{lN}d}' - solution['x_'+i_string] = self.get(i,'x') - solution['u_'+i_string] = self.get(i,'u') - solution['z_'+i_string] = self.get(i,'z') - solution['lam_'+i_string] = self.get(i,'lam') - solution['t_'+i_string] = self.get(i, 't') - solution['sl_'+i_string] = self.get(i, 'sl') - solution['su_'+i_string] = self.get(i, 'su') - if i < self.N: - solution['pi_'+i_string] = self.get(i,'pi') - - for k in list(solution.keys()): - if len(solution[k]) == 0: - del solution[k] - - # save - with open(filename, 'w') as f: - json.dump(solution, f, default=make_object_json_dumpable, indent=4, sort_keys=True) - print("stored current iterate in ", os.path.join(os.getcwd(), filename)) - - - - def dump_last_qp_to_json(self, filename: str = '', overwrite=False): - """ - Dumps the latest QP data into a json file - - :param filename: if not set, use model_name + timestamp + '.json' - :param overwrite: if false and filename exists add timestamp to filename - """ - if filename == '': - filename = f'{self.model_name}_QP.json' - - if not overwrite: - # append timestamp - if os.path.isfile(filename): - filename = filename[:-5] - filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' - - # get QP data: - qp_data = dict() - - lN = len(str(self.N+1)) - for field in self.__qp_dynamics_fields: - for i in range(self.N): - qp_data[f'{field}_{i:0{lN}d}'] = self.get_from_qp_in(i,field) - - for field in self.__qp_constraint_fields + self.__qp_cost_fields: - for i in range(self.N+1): - qp_data[f'{field}_{i:0{lN}d}'] = self.get_from_qp_in(i,field) - - # remove empty fields - for k in list(qp_data.keys()): - if len(qp_data[k]) == 0: - del qp_data[k] - - # save - with open(filename, 'w') as f: - json.dump(qp_data, f, default=make_object_json_dumpable, indent=4, sort_keys=True) - print("stored qp from solver memory in ", os.path.join(os.getcwd(), filename)) - - - - def load_iterate(self, filename): - """ - Loads the iterate stored in json file with filename into the ocp solver. - """ - if not os.path.isfile(filename): - raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) - - with open(filename, 'r') as f: - solution = json.load(f) - - print(f"loading iterate {filename}") - for key in solution.keys(): - (field, stage) = key.split('_') - self.set(int(stage), field, np.array(solution[key])) - - - def get_stats(self, field_): - """ - Get the information of the last solver call. - - :param field: string in ['statistics', 'time_tot', 'time_lin', 'time_sim', 'time_sim_ad', 'time_sim_la', 'time_qp', 'time_qp_solver_call', 'time_reg', 'sqp_iter', 'residuals', 'qp_iter', 'alpha'] - - Available fileds: - - time_tot: total CPU time previous call - - time_lin: CPU time for linearization - - time_sim: CPU time for integrator - - time_sim_ad: CPU time for integrator contribution of external function calls - - time_sim_la: CPU time for integrator contribution of linear algebra - - time_qp: CPU time qp solution - - time_qp_solver_call: CPU time inside qp solver (without converting the QP) - - time_qp_xcond: time_glob: CPU time globalization - - time_solution_sensitivities: CPU time for previous call to eval_param_sens - - time_reg: CPU time regularization - - sqp_iter: number of SQP iterations - - qp_iter: vector of QP iterations for last SQP call - - statistics: table with info about last iteration - - stat_m: number of rows in statistics matrix - - stat_n: number of columns in statistics matrix - - residuals: residuals of last iterate - - alpha: step sizes of SQP iterations - """ - - double_fields = ['time_tot', - 'time_lin', - 'time_sim', - 'time_sim_ad', - 'time_sim_la', - 'time_qp', - 'time_qp_solver_call', - 'time_qp_xcond', - 'time_glob', - 'time_solution_sensitivities', - 'time_reg' - ] - fields = double_fields + [ - 'sqp_iter', - 'qp_iter', - 'statistics', - 'stat_m', - 'stat_n', - 'residuals', - 'alpha', - ] - field = field_.encode('utf-8') - - - if field_ in ['sqp_iter', 'stat_m', 'stat_n']: - out = np.ascontiguousarray(np.zeros((1,)), dtype=np.int64) - out_data = cast(out.ctypes.data, POINTER(c_int64)) - self.shared_lib.ocp_nlp_get.argtypes = [c_void_p, c_void_p, c_char_p, c_void_p] - self.shared_lib.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_data) - return out - - # TODO: just return double instead of np. - elif field_ in double_fields: - out = np.zeros((1,)) - out_data = cast(out.ctypes.data, POINTER(c_double)) - self.shared_lib.ocp_nlp_get.argtypes = [c_void_p, c_void_p, c_char_p, c_void_p] - self.shared_lib.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_data) - return out - - elif field_ == 'statistics': - sqp_iter = self.get_stats("sqp_iter") - stat_m = self.get_stats("stat_m") - stat_n = self.get_stats("stat_n") - min_size = min([stat_m, sqp_iter+1]) - out = np.ascontiguousarray( - np.zeros((stat_n[0]+1, min_size[0])), dtype=np.float64) - out_data = cast(out.ctypes.data, POINTER(c_double)) - self.shared_lib.ocp_nlp_get.argtypes = [c_void_p, c_void_p, c_char_p, c_void_p] - self.shared_lib.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_data) - return out - - elif field_ == 'qp_iter': - full_stats = self.get_stats('statistics') - if self.solver_options['nlp_solver_type'] == 'SQP': - return full_stats[6, :] - elif self.solver_options['nlp_solver_type'] == 'SQP_RTI': - return full_stats[2, :] - - elif field_ == 'alpha': - full_stats = self.get_stats('statistics') - if self.solver_options['nlp_solver_type'] == 'SQP': - return full_stats[7, :] - else: # self.solver_options['nlp_solver_type'] == 'SQP_RTI': - raise Exception("alpha values are not available for SQP_RTI") - - elif field_ == 'residuals': - return self.get_residuals() - - else: - raise Exception(f'AcadosOcpSolver.get_stats(): \'{field}\' is not a valid argument.' - + f'\n Possible values are {fields}.') - - - def get_cost(self): - """ - Returns the cost value of the current solution. - """ - # compute cost internally - self.shared_lib.ocp_nlp_eval_cost.argtypes = [c_void_p, c_void_p, c_void_p] - self.shared_lib.ocp_nlp_eval_cost(self.nlp_solver, self.nlp_in, self.nlp_out) - - # create output array - out = np.ascontiguousarray(np.zeros((1,)), dtype=np.float64) - out_data = cast(out.ctypes.data, POINTER(c_double)) - - # call getter - self.shared_lib.ocp_nlp_get.argtypes = [c_void_p, c_void_p, c_char_p, c_void_p] - - field = "cost_value".encode('utf-8') - self.shared_lib.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_data) - - return out[0] - - - def get_residuals(self, recompute=False): - """ - Returns an array of the form [res_stat, res_eq, res_ineq, res_comp]. - This residual has to be computed for SQP_RTI solver, since it is not available by default. - - - res_stat: stationarity residual - - res_eq: residual wrt equality constraints (dynamics) - - res_ineq: residual wrt inequality constraints (constraints) - - res_comp: residual wrt complementarity conditions - """ - # compute residuals if RTI - if self.solver_options['nlp_solver_type'] == 'SQP_RTI' or recompute: - self.shared_lib.ocp_nlp_eval_residuals.argtypes = [c_void_p, c_void_p, c_void_p] - self.shared_lib.ocp_nlp_eval_residuals(self.nlp_solver, self.nlp_in, self.nlp_out) - - # create output array - out = np.ascontiguousarray(np.zeros((4, 1)), dtype=np.float64) - out_data = cast(out.ctypes.data, POINTER(c_double)) - - # call getters - self.shared_lib.ocp_nlp_get.argtypes = [c_void_p, c_void_p, c_char_p, c_void_p] - - field = "res_stat".encode('utf-8') - self.shared_lib.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_data) - - out_data = cast(out[1].ctypes.data, POINTER(c_double)) - field = "res_eq".encode('utf-8') - self.shared_lib.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_data) - - out_data = cast(out[2].ctypes.data, POINTER(c_double)) - field = "res_ineq".encode('utf-8') - self.shared_lib.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_data) - - out_data = cast(out[3].ctypes.data, POINTER(c_double)) - field = "res_comp".encode('utf-8') - self.shared_lib.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_data) - return out.flatten() - - - # Note: this function should not be used anymore, better use cost_set, constraints_set - def set(self, stage_, field_, value_): - """ - Set numerical data inside the solver. - - :param stage: integer corresponding to shooting node - :param field: string in ['x', 'u', 'pi', 'lam', 't', 'p', 'xdot_guess', 'z_guess'] - - .. note:: regarding lam, t: \n - the inequalities are internally organized in the following order: \n - [ lbu lbx lg lh lphi ubu ubx ug uh uphi; \n - lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi] - - .. note:: pi: multipliers for dynamics equality constraints \n - lam: multipliers for inequalities \n - t: slack variables corresponding to evaluation of all inequalities (at the solution) \n - sl: slack variables of soft lower inequality constraints \n - su: slack variables of soft upper inequality constraints \n - """ - cost_fields = ['y_ref', 'yref'] - constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] - out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] - mem_fields = ['xdot_guess', 'z_guess'] - - # cast value_ to avoid conversion issues - if isinstance(value_, (float, int)): - value_ = np.array([value_]) - value_ = value_.astype(float) - - field = field_.encode('utf-8') - - stage = c_int(stage_) - - # treat parameters separately - if field_ == 'p': - getattr(self.shared_lib, f"{self.model_name}_acados_update_params").argtypes = [c_void_p, c_int, POINTER(c_double), c_int] - getattr(self.shared_lib, f"{self.model_name}_acados_update_params").restype = c_int - - value_data = cast(value_.ctypes.data, POINTER(c_double)) - - assert getattr(self.shared_lib, f"{self.model_name}_acados_update_params")(self.capsule, stage, value_data, value_.shape[0])==0 - else: - if field_ not in constraints_fields + cost_fields + out_fields + mem_fields: - raise Exception(f"AcadosOcpSolver.set(): '{field}' is not a valid argument.\n" - f" Possible values are {constraints_fields + cost_fields + out_fields + mem_fields + ['p']}.") - - self.shared_lib.ocp_nlp_dims_get_from_attr.argtypes = \ - [c_void_p, c_void_p, c_void_p, c_int, c_char_p] - self.shared_lib.ocp_nlp_dims_get_from_attr.restype = c_int - - dims = self.shared_lib.ocp_nlp_dims_get_from_attr(self.nlp_config, \ - self.nlp_dims, self.nlp_out, stage_, field) - - if value_.shape[0] != dims: - msg = f'AcadosOcpSolver.set(): mismatching dimension for field "{field_}" ' - msg += f'with dimension {dims} (you have {value_.shape[0]})' - raise Exception(msg) - - value_data = cast(value_.ctypes.data, POINTER(c_double)) - value_data_p = cast((value_data), c_void_p) - - if field_ in constraints_fields: - self.shared_lib.ocp_nlp_constraints_model_set.argtypes = \ - [c_void_p, c_void_p, c_void_p, c_int, c_char_p, c_void_p] - self.shared_lib.ocp_nlp_constraints_model_set(self.nlp_config, \ - self.nlp_dims, self.nlp_in, stage, field, value_data_p) - elif field_ in cost_fields: - self.shared_lib.ocp_nlp_cost_model_set.argtypes = \ - [c_void_p, c_void_p, c_void_p, c_int, c_char_p, c_void_p] - self.shared_lib.ocp_nlp_cost_model_set(self.nlp_config, \ - self.nlp_dims, self.nlp_in, stage, field, value_data_p) - elif field_ in out_fields: - self.shared_lib.ocp_nlp_out_set.argtypes = \ - [c_void_p, c_void_p, c_void_p, c_int, c_char_p, c_void_p] - self.shared_lib.ocp_nlp_out_set(self.nlp_config, \ - self.nlp_dims, self.nlp_out, stage, field, value_data_p) - elif field_ in mem_fields: - self.shared_lib.ocp_nlp_set.argtypes = \ - [c_void_p, c_void_p, c_int, c_char_p, c_void_p] - self.shared_lib.ocp_nlp_set(self.nlp_config, \ - self.nlp_solver, stage, field, value_data_p) - # also set z_guess, when setting z. - if field_ == 'z': - field = 'z_guess'.encode('utf-8') - self.shared_lib.ocp_nlp_set.argtypes = \ - [c_void_p, c_void_p, c_int, c_char_p, c_void_p] - self.shared_lib.ocp_nlp_set(self.nlp_config, \ - self.nlp_solver, stage, field, value_data_p) - return - - - def cost_set(self, stage_, field_, value_, api='warn'): - """ - Set numerical data in the cost module of the solver. - - :param stage: integer corresponding to shooting node - :param field: string, e.g. 'yref', 'W', 'ext_cost_num_hess', 'zl', 'zu', 'Zl', 'Zu' - :param value: of appropriate size - """ - # cast value_ to avoid conversion issues - if isinstance(value_, (float, int)): - value_ = np.array([value_]) - value_ = value_.astype(float) - - field = field_ - field = field.encode('utf-8') - - stage = c_int(stage_) - self.shared_lib.ocp_nlp_cost_dims_get_from_attr.argtypes = \ - [c_void_p, c_void_p, c_void_p, c_int, c_char_p, POINTER(c_int)] - self.shared_lib.ocp_nlp_cost_dims_get_from_attr.restype = c_int - - dims = np.ascontiguousarray(np.zeros((2,)), dtype=np.intc) - dims_data = cast(dims.ctypes.data, POINTER(c_int)) - - self.shared_lib.ocp_nlp_cost_dims_get_from_attr(self.nlp_config, \ - self.nlp_dims, self.nlp_out, stage_, field, dims_data) - - value_shape = value_.shape - if len(value_shape) == 1: - value_shape = (value_shape[0], 0) - - elif len(value_shape) == 2: - if api=='old': - pass - elif api=='warn': - if not np.all(np.ravel(value_, order='F')==np.ravel(value_, order='K')): - raise Exception("Ambiguity in API detected.\n" - "Are you making an acados model from scrach? Add api='new' to cost_set and carry on.\n" - "Are you seeing this error suddenly in previously running code? Read on.\n" - f" You are relying on a now-fixed bug in cost_set for field '{field_}'.\n" + - " acados_template now correctly passes on any matrices to acados in column major format.\n" + - " Two options to fix this error: \n" + - " * Add api='old' to cost_set to restore old incorrect behaviour\n" + - " * Add api='new' to cost_set and remove any unnatural manipulation of the value argument " + - "such as non-mathematical transposes, reshaping, casting to fortran order, etc... " + - "If there is no such manipulation, then you have probably been getting an incorrect solution before.") - # Get elements in column major order - value_ = np.ravel(value_, order='F') - elif api=='new': - # Get elements in column major order - value_ = np.ravel(value_, order='F') - else: - raise Exception("Unknown api: '{}'".format(api)) - - if value_shape != tuple(dims): - raise Exception('AcadosOcpSolver.cost_set(): mismatching dimension' + - f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') - - value_data = cast(value_.ctypes.data, POINTER(c_double)) - value_data_p = cast((value_data), c_void_p) - - self.shared_lib.ocp_nlp_cost_model_set.argtypes = \ - [c_void_p, c_void_p, c_void_p, c_int, c_char_p, c_void_p] - self.shared_lib.ocp_nlp_cost_model_set(self.nlp_config, \ - self.nlp_dims, self.nlp_in, stage, field, value_data_p) - - return - - - def constraints_set(self, stage_, field_, value_, api='warn'): - """ - Set numerical data in the constraint module of the solver. - - :param stage: integer corresponding to shooting node - :param field: string in ['lbx', 'ubx', 'lbu', 'ubu', 'lg', 'ug', 'lh', 'uh', 'uphi', 'C', 'D'] - :param value: of appropriate size - """ - # cast value_ to avoid conversion issues - if isinstance(value_, (float, int)): - value_ = np.array([value_]) - value_ = value_.astype(float) - - field = field_ - field = field.encode('utf-8') - - stage = c_int(stage_) - self.shared_lib.ocp_nlp_constraint_dims_get_from_attr.argtypes = \ - [c_void_p, c_void_p, c_void_p, c_int, c_char_p, POINTER(c_int)] - self.shared_lib.ocp_nlp_constraint_dims_get_from_attr.restype = c_int - - dims = np.ascontiguousarray(np.zeros((2,)), dtype=np.intc) - dims_data = cast(dims.ctypes.data, POINTER(c_int)) - - self.shared_lib.ocp_nlp_constraint_dims_get_from_attr(self.nlp_config, \ - self.nlp_dims, self.nlp_out, stage_, field, dims_data) - - value_shape = value_.shape - if len(value_shape) == 1: - value_shape = (value_shape[0], 0) - elif len(value_shape) == 2: - if api=='old': - pass - elif api=='warn': - if not np.all(np.ravel(value_, order='F')==np.ravel(value_, order='K')): - raise Exception("Ambiguity in API detected.\n" - "Are you making an acados model from scrach? Add api='new' to constraints_set and carry on.\n" - "Are you seeing this error suddenly in previously running code? Read on.\n" - f" You are relying on a now-fixed bug in constraints_set for field '{field}'.\n" + - " acados_template now correctly passes on any matrices to acados in column major format.\n" + - " Two options to fix this error: \n" + - " * Add api='old' to constraints_set to restore old incorrect behaviour\n" + - " * Add api='new' to constraints_set and remove any unnatural manipulation of the value argument " + - "such as non-mathematical transposes, reshaping, casting to fortran order, etc... " + - "If there is no such manipulation, then you have probably been getting an incorrect solution before.") - # Get elements in column major order - value_ = np.ravel(value_, order='F') - elif api=='new': - # Get elements in column major order - value_ = np.ravel(value_, order='F') - else: - raise Exception(f"Unknown api: '{api}'") - - if value_shape != tuple(dims): - raise Exception(f'AcadosOcpSolver.constraints_set(): mismatching dimension' + - f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') - - value_data = cast(value_.ctypes.data, POINTER(c_double)) - value_data_p = cast((value_data), c_void_p) - - self.shared_lib.ocp_nlp_constraints_model_set.argtypes = \ - [c_void_p, c_void_p, c_void_p, c_int, c_char_p, c_void_p] - self.shared_lib.ocp_nlp_constraints_model_set(self.nlp_config, \ - self.nlp_dims, self.nlp_in, stage, field, value_data_p) - - return - - - def get_from_qp_in(self, stage_: int, field_: str): - """ - Get numerical data from the current QP. - - :param stage: integer corresponding to shooting node - :param field: string in ['A', 'B', 'b', 'Q', 'R', 'S', 'q', 'r', 'C', 'D', 'lg', 'ug', 'lbx', 'ubx', 'lbu', 'ubu'] - """ - # idx* should be added too.. - if not isinstance(stage_, int): - raise TypeError("stage should be int") - if stage_ > self.N: - raise Exception("stage should be <= self.N") - if field_ in self.__qp_dynamics_fields and stage_ >= self.N: - raise ValueError(f"dynamics field {field_} not available at terminal stage") - if field_ not in self.__qp_dynamics_fields + self.__qp_cost_fields + self.__qp_constraint_fields: - raise Exception(f"field {field_} not supported.") - - field = field_.encode('utf-8') - stage = c_int(stage_) - - # get dims - self.shared_lib.ocp_nlp_qp_dims_get_from_attr.argtypes = \ - [c_void_p, c_void_p, c_void_p, c_int, c_char_p, POINTER(c_int)] - self.shared_lib.ocp_nlp_qp_dims_get_from_attr.restype = c_int - - dims = np.ascontiguousarray(np.zeros((2,)), dtype=np.intc) - dims_data = cast(dims.ctypes.data, POINTER(c_int)) - - self.shared_lib.ocp_nlp_qp_dims_get_from_attr(self.nlp_config, \ - self.nlp_dims, self.nlp_out, stage_, field, dims_data) - - # create output data - out = np.ascontiguousarray(np.zeros((np.prod(dims),)), dtype=np.float64) - out = out.reshape(dims[0], dims[1], order='F') - - out_data = cast(out.ctypes.data, POINTER(c_double)) - out_data_p = cast((out_data), c_void_p) - - # call getter - self.shared_lib.ocp_nlp_get_at_stage.argtypes = \ - [c_void_p, c_void_p, c_void_p, c_int, c_char_p, c_void_p] - self.shared_lib.ocp_nlp_get_at_stage(self.nlp_config, \ - self.nlp_dims, self.nlp_solver, stage, field, out_data_p) - - return out - - - def options_set(self, field_, value_): - """ - Set options of the solver. - - :param field: string, e.g. 'print_level', 'rti_phase', 'initialize_t_slacks', 'step_length', 'alpha_min', 'alpha_reduction', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0' - - :param value: of type int, float, string - - - qp_tol_stat: QP solver tolerance stationarity - - qp_tol_eq: QP solver tolerance equalities - - qp_tol_ineq: QP solver tolerance inequalities - - qp_tol_comp: QP solver tolerance complementarity - - qp_tau_min: for HPIPM QP solvers: minimum value of barrier parameter in HPIPM - - qp_mu0: for HPIPM QP solvers: initial value for complementarity slackness - - warm_start_first_qp: indicates if first QP in SQP is warm_started - """ - int_fields = ['print_level', 'rti_phase', 'initialize_t_slacks', 'qp_warm_start', - 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'warm_start_first_qp'] - double_fields = ['step_length', 'tol_eq', 'tol_stat', 'tol_ineq', 'tol_comp', 'alpha_min', 'alpha_reduction', - 'eps_sufficient_descent', 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'] - string_fields = ['globalization'] - - # check field availability and type - if field_ in int_fields: - if not isinstance(value_, int): - raise Exception(f'solver option \'{field_}\' must be of type int. You have {type(value_)}.') - else: - value_ctypes = c_int(value_) - - elif field_ in double_fields: - if not isinstance(value_, float): - raise Exception(f'solver option \'{field_}\' must be of type float. You have {type(value_)}.') - else: - value_ctypes = c_double(value_) - - elif field_ in string_fields: - if not isinstance(value_, str): - raise Exception(f'solver option \'{field_}\' must be of type str. You have {type(value_)}.') - else: - value_ctypes = value_.encode('utf-8') - else: - fields = ', '.join(int_fields + double_fields + string_fields) - raise Exception(f'AcadosOcpSolver.options_set() does not support field \'{field_}\'.\n'\ - f' Possible values are {fields}.') - - - if field_ == 'rti_phase': - if value_ < 0 or value_ > 2: - raise Exception('AcadosOcpSolver.options_set(): argument \'rti_phase\' can ' - 'take only values 0, 1, 2 for SQP-RTI-type solvers') - if self.solver_options['nlp_solver_type'] != 'SQP_RTI' and value_ > 0: - raise Exception('AcadosOcpSolver.options_set(): argument \'rti_phase\' can ' - 'take only value 0 for SQP-type solvers') - - # encode - field = field_ - field = field.encode('utf-8') - - # call C interface - if field_ in string_fields: - self.shared_lib.ocp_nlp_solver_opts_set.argtypes = \ - [c_void_p, c_void_p, c_char_p, c_char_p] - self.shared_lib.ocp_nlp_solver_opts_set(self.nlp_config, \ - self.nlp_opts, field, value_ctypes) - else: - self.shared_lib.ocp_nlp_solver_opts_set.argtypes = \ - [c_void_p, c_void_p, c_char_p, c_void_p] - self.shared_lib.ocp_nlp_solver_opts_set(self.nlp_config, \ - self.nlp_opts, field, byref(value_ctypes)) - return - - - def set_params_sparse(self, stage_, idx_values_, param_values_): - """ - set parameters of the solvers external function partially: - Pseudo: solver.param[idx_values_] = param_values_; - Parameters: - :param stage_: integer corresponding to shooting node - :param idx_values_: 0 based np array (or iterable) of integers: indices of parameter to be set - :param param_values_: new parameter values as numpy array - """ - - # if not isinstance(idx_values_, np.ndarray) or not issubclass(type(idx_values_[0]), np.integer): - # raise Exception('idx_values_ must be np.array of integers.') - - if not isinstance(param_values_, np.ndarray): - raise Exception('param_values_ must be np.array.') - elif np.float64 != param_values_.dtype: - raise TypeError('param_values_ must be np.array of float64.') - - if param_values_.shape[0] != len(idx_values_): - raise Exception(f'param_values_ and idx_values_ must be of the same size.' + - f' Got sizes idx {param_values_.shape[0]}, param_values {len(idx_values_)}.') - - if any(idx_values_ >= self.acados_ocp.dims.np): - raise Exception(f'idx_values_ contains value >= np = {self.acados_ocp.dims.np}') - - stage = c_int(stage_) - n_update = c_int(len(param_values_)) - - param_data = cast(param_values_.ctypes.data, POINTER(c_double)) - c_idx_values = np.ascontiguousarray(idx_values_, dtype=np.intc) - idx_data = cast(c_idx_values.ctypes.data, POINTER(c_int)) - - getattr(self.shared_lib, f"{self.model_name}_acados_update_params_sparse").argtypes = \ - [c_void_p, c_int, POINTER(c_int), POINTER(c_double), c_int] - getattr(self.shared_lib, f"{self.model_name}_acados_update_params_sparse").restype = c_int - getattr(self.shared_lib, f"{self.model_name}_acados_update_params_sparse") \ - (self.capsule, stage, idx_data, param_data, n_update) - - def __del__(self): - if self.solver_created: - getattr(self.shared_lib, f"{self.model_name}_acados_free").argtypes = [c_void_p] - getattr(self.shared_lib, f"{self.model_name}_acados_free").restype = c_int - getattr(self.shared_lib, f"{self.model_name}_acados_free")(self.capsule) - - getattr(self.shared_lib, f"{self.model_name}_acados_free_capsule").argtypes = [c_void_p] - getattr(self.shared_lib, f"{self.model_name}_acados_free_capsule").restype = c_int - getattr(self.shared_lib, f"{self.model_name}_acados_free_capsule")(self.capsule) - - try: - self.dlclose(self.shared_lib._handle) - except: - print(f"WARNING: acados Python interface could not close shared_lib handle of AcadosOcpSolver {self.model_name}.\n", - "Attempting to create a new one with the same name will likely result in the old one being used!") - pass diff --git a/third_party/acados/acados_template/acados_ocp_solver_pyx.pyx b/third_party/acados/acados_template/acados_ocp_solver_pyx.pyx deleted file mode 100644 index bc03ba086f..0000000000 --- a/third_party/acados/acados_template/acados_ocp_solver_pyx.pyx +++ /dev/null @@ -1,794 +0,0 @@ -# -# Copyright (c) The acados authors. -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# -# cython: language_level=3 -# cython: profile=False -# distutils: language=c - -cimport cython -from libc cimport string - -cimport acados_solver_common -# TODO: make this import more clear? it is not a general solver, but problem specific. -cimport acados_solver - -cimport numpy as cnp - -import os -from datetime import datetime -import numpy as np - - -cdef class AcadosOcpSolverCython: - """ - Class to interact with the acados ocp solver C object. - """ - - cdef acados_solver.nlp_solver_capsule *capsule - cdef void *nlp_opts - cdef acados_solver_common.ocp_nlp_dims *nlp_dims - cdef acados_solver_common.ocp_nlp_config *nlp_config - cdef acados_solver_common.ocp_nlp_out *nlp_out - cdef acados_solver_common.ocp_nlp_out *sens_out - cdef acados_solver_common.ocp_nlp_in *nlp_in - cdef acados_solver_common.ocp_nlp_solver *nlp_solver - - cdef bint solver_created - - cdef str model_name - cdef int N - - cdef str nlp_solver_type - - def __cinit__(self, model_name, nlp_solver_type, N): - - self.solver_created = False - - self.N = N - self.model_name = model_name - self.nlp_solver_type = nlp_solver_type - - # create capsule - self.capsule = acados_solver.acados_create_capsule() - - # create solver - assert acados_solver.acados_create(self.capsule) == 0 - self.solver_created = True - - # get pointers solver - self.__get_pointers_solver() - - - def __get_pointers_solver(self): - """ - Private function to get the pointers for solver - """ - # get pointers solver - self.nlp_opts = acados_solver.acados_get_nlp_opts(self.capsule) - self.nlp_dims = acados_solver.acados_get_nlp_dims(self.capsule) - self.nlp_config = acados_solver.acados_get_nlp_config(self.capsule) - self.nlp_out = acados_solver.acados_get_nlp_out(self.capsule) - self.sens_out = acados_solver.acados_get_sens_out(self.capsule) - self.nlp_in = acados_solver.acados_get_nlp_in(self.capsule) - self.nlp_solver = acados_solver.acados_get_nlp_solver(self.capsule) - - - def solve_for_x0(self, x0_bar): - """ - Wrapper around `solve()` which sets initial state constraint, solves the OCP, and returns u0. - """ - self.set(0, "lbx", x0_bar) - self.set(0, "ubx", x0_bar) - - status = self.solve() - - if status == 2: - print("Warning: acados_ocp_solver reached maximum iterations.") - elif status != 0: - raise Exception(f'acados acados_ocp_solver returned status {status}') - - u0 = self.get(0, "u") - return u0 - - - def solve(self): - """ - Solve the ocp with current input. - """ - return acados_solver.acados_solve(self.capsule) - - - def reset(self, reset_qp_solver_mem=1): - """ - Sets current iterate to all zeros. - """ - return acados_solver.acados_reset(self.capsule, reset_qp_solver_mem) - - - def custom_update(self, data_): - """ - A custom function that can be implemented by a user to be called between solver calls. - By default this does nothing. - The idea is to have a convenient wrapper to do complex updates of parameters and numerical data efficiently in C, - in a function that is compiled into the solver library and can be conveniently used in the Python environment. - """ - data_len = len(data_) - cdef cnp.ndarray[cnp.float64_t, ndim=1] data = np.ascontiguousarray(data_, dtype=np.float64) - - return acados_solver.acados_custom_update(self.capsule, data.data, data_len) - - - def set_new_time_steps(self, new_time_steps): - """ - Set new time steps. - Recreates the solver if N changes. - - :param new_time_steps: 1 dimensional np array of new time steps for the solver - - .. note:: This allows for different use-cases: either set a new size of time-steps or a new distribution of - the shooting nodes without changing the number, e.g., to reach a different final time. Both cases - do not require a new code export and compilation. - """ - - raise NotImplementedError("AcadosOcpSolverCython: does not support set_new_time_steps() since it is only a prototyping feature") - # # unlikely but still possible - # if not self.solver_created: - # raise Exception('Solver was not yet created!') - - # ## check if time steps really changed in value - # # get time steps - # cdef cnp.ndarray[cnp.float64_t, ndim=1] old_time_steps = np.ascontiguousarray(np.zeros((self.N,)), dtype=np.float64) - # assert acados_solver.acados_get_time_steps(self.capsule, self.N, old_time_steps.data) - - # if np.array_equal(old_time_steps, new_time_steps): - # return - - # N = new_time_steps.size - # cdef cnp.ndarray[cnp.float64_t, ndim=1] value = np.ascontiguousarray(new_time_steps, dtype=np.float64) - - # # check if recreation of acados is necessary (no need to recreate acados if sizes are identical) - # if len(old_time_steps) == N: - # assert acados_solver.acados_update_time_steps(self.capsule, N, value.data) == 0 - - # else: # recreate the solver with the new time steps - # self.solver_created = False - - # # delete old memory (analog to __del__) - # acados_solver.acados_free(self.capsule) - - # # create solver with new time steps - # assert acados_solver.acados_create_with_discretization(self.capsule, N, value.data) == 0 - - # self.solver_created = True - - # # get pointers solver - # self.__get_pointers_solver() - - # # store time_steps, N - # self.time_steps = new_time_steps - # self.N = N - - - def update_qp_solver_cond_N(self, qp_solver_cond_N: int): - """ - Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver. - This function is relevant for code reuse, i.e., if either `set_new_time_steps(...)` is used or - the influence of a different `qp_solver_cond_N` is studied without code export and compilation. - :param qp_solver_cond_N: new number of condensing stages for the solver - - .. note:: This function can only be used in combination with a partial condensing QP solver. - - .. note:: After `set_new_time_steps(...)` is used and depending on the new number of time steps it might be - necessary to change `qp_solver_cond_N` as well (using this function), i.e., typically - `qp_solver_cond_N < N`. - """ - raise NotImplementedError("AcadosOcpSolverCython: does not support update_qp_solver_cond_N() since it is only a prototyping feature") - - # # unlikely but still possible - # if not self.solver_created: - # raise Exception('Solver was not yet created!') - # if self.N < qp_solver_cond_N: - # raise Exception('Setting qp_solver_cond_N to be larger than N does not work!') - # if self.qp_solver_cond_N != qp_solver_cond_N: - # self.solver_created = False - - # # recreate the solver - # acados_solver.acados_update_qp_solver_cond_N(self.capsule, qp_solver_cond_N) - - # # store the new value - # self.qp_solver_cond_N = qp_solver_cond_N - # self.solver_created = True - - # # get pointers solver - # self.__get_pointers_solver() - - - def eval_param_sens(self, index, stage=0, field="ex"): - """ - Calculate the sensitivity of the curent solution with respect to the initial state component of index - - :param index: integer corresponding to initial state index in range(nx) - """ - - field_ = field - field = field_.encode('utf-8') - - # checks - if not isinstance(index, int): - raise Exception('AcadosOcpSolverCython.eval_param_sens(): index must be Integer.') - - cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) - - if index < 0 or index > nx: - raise Exception(f'AcadosOcpSolverCython.eval_param_sens(): index must be in [0, nx-1], got: {index}.') - - # actual eval_param - acados_solver_common.ocp_nlp_eval_param_sens(self.nlp_solver, field, stage, index, self.sens_out) - - return - - - def get(self, int stage, str field_): - """ - Get the last solution of the solver: - - :param stage: integer corresponding to shooting node - :param field: string in ['x', 'u', 'z', 'pi', 'lam', 't', 'sl', 'su',] - - .. note:: regarding lam, t: \n - the inequalities are internally organized in the following order: \n - [ lbu lbx lg lh lphi ubu ubx ug uh uphi; \n - lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi] - - .. note:: pi: multipliers for dynamics equality constraints \n - lam: multipliers for inequalities \n - t: slack variables corresponding to evaluation of all inequalities (at the solution) \n - sl: slack variables of soft lower inequality constraints \n - su: slack variables of soft upper inequality constraints \n - """ - - out_fields = ['x', 'u', 'z', 'pi', 'lam', 't', 'sl', 'su'] - field = field_.encode('utf-8') - - if field_ not in out_fields: - raise Exception('AcadosOcpSolverCython.get(): {} is an invalid argument.\ - \n Possible values are {}.'.format(field_, out_fields)) - - if stage < 0 or stage > self.N: - raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) - - if stage == self.N and field_ == 'pi': - raise Exception('AcadosOcpSolverCython.get(): field {} does not exist at final stage {}.'\ - .format(field_, stage)) - - cdef int dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, - self.nlp_dims, self.nlp_out, stage, field) - - cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((dims,)) - acados_solver_common.ocp_nlp_out_get(self.nlp_config, \ - self.nlp_dims, self.nlp_out, stage, field, out.data) - - return out - - - def print_statistics(self): - """ - prints statistics of previous solver run as a table: - - iter: iteration number - - res_stat: stationarity residual - - res_eq: residual wrt equality constraints (dynamics) - - res_ineq: residual wrt inequality constraints (constraints) - - res_comp: residual wrt complementarity conditions - - qp_stat: status of QP solver - - qp_iter: number of QP iterations - - qp_res_stat: stationarity residual of the last QP solution - - qp_res_eq: residual wrt equality constraints (dynamics) of the last QP solution - - qp_res_ineq: residual wrt inequality constraints (constraints) of the last QP solution - - qp_res_comp: residual wrt complementarity conditions of the last QP solution - """ - acados_solver.acados_print_stats(self.capsule) - - - def store_iterate(self, filename='', overwrite=False): - """ - Stores the current iterate of the ocp solver in a json file. - - :param filename: if not set, use model_name + timestamp + '.json' - :param overwrite: if false and filename exists add timestamp to filename - """ - import json - if filename == '': - filename += self.model_name + '_' + 'iterate' + '.json' - - if not overwrite: - # append timestamp - if os.path.isfile(filename): - filename = filename[:-5] - filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' - - # get iterate: - solution = dict() - - lN = len(str(self.N+1)) - for i in range(self.N+1): - i_string = f'{i:0{lN}d}' - solution['x_'+i_string] = self.get(i,'x') - solution['u_'+i_string] = self.get(i,'u') - solution['z_'+i_string] = self.get(i,'z') - solution['lam_'+i_string] = self.get(i,'lam') - solution['t_'+i_string] = self.get(i, 't') - solution['sl_'+i_string] = self.get(i, 'sl') - solution['su_'+i_string] = self.get(i, 'su') - if i < self.N: - solution['pi_'+i_string] = self.get(i,'pi') - - for k in list(solution.keys()): - if len(solution[k]) == 0: - del solution[k] - - # save - with open(filename, 'w') as f: - json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) - print("stored current iterate in ", os.path.join(os.getcwd(), filename)) - - - def load_iterate(self, filename): - """ - Loads the iterate stored in json file with filename into the ocp solver. - """ - import json - if not os.path.isfile(filename): - raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) - - with open(filename, 'r') as f: - solution = json.load(f) - - for key in solution.keys(): - (field, stage) = key.split('_') - self.set(int(stage), field, np.array(solution[key])) - - - def get_stats(self, field_): - """ - Get the information of the last solver call. - - :param field: string in ['statistics', 'time_tot', 'time_lin', 'time_sim', 'time_sim_ad', 'time_sim_la', 'time_qp', 'time_qp_solver_call', 'time_reg', 'sqp_iter'] - Available fileds: - - time_tot: total CPU time previous call - - time_lin: CPU time for linearization - - time_sim: CPU time for integrator - - time_sim_ad: CPU time for integrator contribution of external function calls - - time_sim_la: CPU time for integrator contribution of linear algebra - - time_qp: CPU time qp solution - - time_qp_solver_call: CPU time inside qp solver (without converting the QP) - - time_qp_xcond: time_glob: CPU time globalization - - time_solution_sensitivities: CPU time for previous call to eval_param_sens - - time_reg: CPU time regularization - - sqp_iter: number of SQP iterations - - qp_iter: vector of QP iterations for last SQP call - - statistics: table with info about last iteration - - stat_m: number of rows in statistics matrix - - stat_n: number of columns in statistics matrix - - residuals: residuals of last iterate - - alpha: step sizes of SQP iterations - """ - - double_fields = ['time_tot', - 'time_lin', - 'time_sim', - 'time_sim_ad', - 'time_sim_la', - 'time_qp', - 'time_qp_solver_call', - 'time_qp_xcond', - 'time_glob', - 'time_solution_sensitivities', - 'time_reg' - ] - fields = double_fields + [ - 'sqp_iter', - 'qp_iter', - 'statistics', - 'stat_m', - 'stat_n', - 'residuals', - 'alpha', - ] - field = field_.encode('utf-8') - - if field_ in ['sqp_iter', 'stat_m', 'stat_n']: - return self.__get_stat_int(field) - - elif field_ in double_fields: - return self.__get_stat_double(field) - - elif field_ == 'statistics': - sqp_iter = self.get_stats("sqp_iter") - stat_m = self.get_stats("stat_m") - stat_n = self.get_stats("stat_n") - min_size = min([stat_m, sqp_iter+1]) - return self.__get_stat_matrix(field, stat_n+1, min_size) - - elif field_ == 'qp_iter': - full_stats = self.get_stats('statistics') - if self.nlp_solver_type == 'SQP': - return full_stats[6, :] - elif self.nlp_solver_type == 'SQP_RTI': - return full_stats[2, :] - - elif field_ == 'alpha': - full_stats = self.get_stats('statistics') - if self.nlp_solver_type == 'SQP': - return full_stats[7, :] - else: # self.nlp_solver_type == 'SQP_RTI': - raise Exception("alpha values are not available for SQP_RTI") - - elif field_ == 'residuals': - return self.get_residuals() - - else: - raise NotImplementedError("TODO!") - - - def __get_stat_int(self, field): - cdef int out - acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) - return out - - def __get_stat_double(self, field): - cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) - acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) - return out - - def __get_stat_matrix(self, field, n, m): - cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) - acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) - return out_mat - - - def get_cost(self): - """ - Returns the cost value of the current solution. - """ - # compute cost internally - acados_solver_common.ocp_nlp_eval_cost(self.nlp_solver, self.nlp_in, self.nlp_out) - - # create output - cdef double out - - # call getter - acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, "cost_value", &out) - - return out - - - def get_residuals(self, recompute=False): - """ - Returns an array of the form [res_stat, res_eq, res_ineq, res_comp]. - """ - # compute residuals if RTI - if self.nlp_solver_type == 'SQP_RTI' or recompute: - acados_solver_common.ocp_nlp_eval_residuals(self.nlp_solver, self.nlp_in, self.nlp_out) - - # create output array - cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.ascontiguousarray(np.zeros((4,), dtype=np.float64)) - cdef double double_value - - field = "res_stat".encode('utf-8') - acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) - out[0] = double_value - - field = "res_eq".encode('utf-8') - acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) - out[1] = double_value - - field = "res_ineq".encode('utf-8') - acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) - out[2] = double_value - - field = "res_comp".encode('utf-8') - acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) - out[3] = double_value - - return out - - - # Note: this function should not be used anymore, better use cost_set, constraints_set - def set(self, int stage, str field_, value_): - - """ - Set numerical data inside the solver. - - :param stage: integer corresponding to shooting node - :param field: string in ['x', 'u', 'pi', 'lam', 't', 'p'] - - .. note:: regarding lam, t: \n - the inequalities are internally organized in the following order: \n - [ lbu lbx lg lh lphi ubu ubx ug uh uphi; \n - lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi] - - .. note:: pi: multipliers for dynamics equality constraints \n - lam: multipliers for inequalities \n - t: slack variables corresponding to evaluation of all inequalities (at the solution) \n - sl: slack variables of soft lower inequality constraints \n - su: slack variables of soft upper inequality constraints \n - """ - if not isinstance(value_, np.ndarray): - raise Exception(f"set: value must be numpy array, got {type(value_)}.") - cost_fields = ['y_ref', 'yref'] - constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] - out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] - mem_fields = ['xdot_guess', 'z_guess'] - - field = field_.encode('utf-8') - - cdef cnp.ndarray[cnp.float64_t, ndim=1] value = np.ascontiguousarray(value_, dtype=np.float64) - - # treat parameters separately - if field_ == 'p': - assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 - else: - if field_ not in constraints_fields + cost_fields + out_fields: - raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ - \nPossible values are {}.".format(field, \ - constraints_fields + cost_fields + out_fields + ['p'])) - - dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, - self.nlp_dims, self.nlp_out, stage, field) - - if value_.shape[0] != dims: - msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) - msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) - raise Exception(msg) - - if field_ in constraints_fields: - acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, - self.nlp_dims, self.nlp_in, stage, field, value.data) - elif field_ in cost_fields: - acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, - self.nlp_dims, self.nlp_in, stage, field, value.data) - elif field_ in out_fields: - acados_solver_common.ocp_nlp_out_set(self.nlp_config, - self.nlp_dims, self.nlp_out, stage, field, value.data) - elif field_ in mem_fields: - acados_solver_common.ocp_nlp_set(self.nlp_config, \ - self.nlp_solver, stage, field, value.data) - - if field_ == 'z': - field = 'z_guess'.encode('utf-8') - acados_solver_common.ocp_nlp_set(self.nlp_config, \ - self.nlp_solver, stage, field, value.data) - return - - def cost_set(self, int stage, str field_, value_): - """ - Set numerical data in the cost module of the solver. - - :param stage: integer corresponding to shooting node - :param field: string, e.g. 'yref', 'W', 'ext_cost_num_hess' - :param value: of appropriate size - """ - if not isinstance(value_, np.ndarray): - raise Exception(f"cost_set: value must be numpy array, got {type(value_)}.") - field = field_.encode('utf-8') - - cdef int dims[2] - acados_solver_common.ocp_nlp_cost_dims_get_from_attr(self.nlp_config, \ - self.nlp_dims, self.nlp_out, stage, field, &dims[0]) - - cdef double[::1,:] value - - value_shape = value_.shape - if len(value_shape) == 1: - value_shape = (value_shape[0], 0) - value = np.asfortranarray(value_[None,:]) - - elif len(value_shape) == 2: - # Get elements in column major order - value = np.asfortranarray(value_) - - if value_shape[0] != dims[0] or value_shape[1] != dims[1]: - raise Exception('AcadosOcpSolverCython.cost_set(): mismatching dimension' + - f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') - - acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, \ - self.nlp_dims, self.nlp_in, stage, field, &value[0][0]) - - - def constraints_set(self, int stage, str field_, value_): - """ - Set numerical data in the constraint module of the solver. - - :param stage: integer corresponding to shooting node - :param field: string in ['lbx', 'ubx', 'lbu', 'ubu', 'lg', 'ug', 'lh', 'uh', 'uphi', 'C', 'D'] - :param value: of appropriate size - """ - if not isinstance(value_, np.ndarray): - raise Exception(f"constraints_set: value must be numpy array, got {type(value_)}.") - - field = field_.encode('utf-8') - - cdef int dims[2] - acados_solver_common.ocp_nlp_constraint_dims_get_from_attr(self.nlp_config, \ - self.nlp_dims, self.nlp_out, stage, field, &dims[0]) - - cdef double[::1,:] value - - value_shape = value_.shape - if len(value_shape) == 1: - value_shape = (value_shape[0], 0) - value = np.asfortranarray(value_[None,:]) - - elif len(value_shape) == 2: - # Get elements in column major order - value = np.asfortranarray(value_) - - if value_shape != tuple(dims): - raise Exception(f'AcadosOcpSolverCython.constraints_set(): mismatching dimension' + - f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') - - acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, \ - self.nlp_dims, self.nlp_in, stage, field, &value[0][0]) - - return - - - def get_from_qp_in(self, int stage, str field_): - """ - Get numerical data from the dynamics module of the solver: - - :param stage: integer corresponding to shooting node - :param field: string, e.g. 'A' - """ - field = field_.encode('utf-8') - - # get dims - cdef int[2] dims - acados_solver_common.ocp_nlp_qp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, stage, field, &dims[0]) - - # create output data - cdef cnp.ndarray[cnp.float64_t, ndim=2] out = np.zeros((dims[0], dims[1]), order='F') - - # call getter - acados_solver_common.ocp_nlp_get_at_stage(self.nlp_config, self.nlp_dims, self.nlp_solver, stage, field, out.data) - - return out - - - def options_set(self, str field_, value_): - """ - Set options of the solver. - - :param field: string, e.g. 'print_level', 'rti_phase', 'initialize_t_slacks', 'step_length', 'alpha_min', 'alpha_reduction', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0' - - :param value: of type int, float, string - - - qp_tol_stat: QP solver tolerance stationarity - - qp_tol_eq: QP solver tolerance equalities - - qp_tol_ineq: QP solver tolerance inequalities - - qp_tol_comp: QP solver tolerance complementarity - - qp_tau_min: for HPIPM QP solvers: minimum value of barrier parameter in HPIPM - - qp_mu0: for HPIPM QP solvers: initial value for complementarity slackness - - warm_start_first_qp: indicates if first QP in SQP is warm_started - """ - int_fields = ['print_level', 'rti_phase', 'initialize_t_slacks', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'warm_start_first_qp'] - double_fields = ['step_length', 'tol_eq', 'tol_stat', 'tol_ineq', 'tol_comp', 'alpha_min', 'alpha_reduction', 'eps_sufficient_descent', - 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'] - string_fields = ['globalization'] - - # encode - field = field_.encode('utf-8') - - cdef int int_value - cdef double double_value - cdef unsigned char[::1] string_value - - # check field availability and type - if field_ in int_fields: - if not isinstance(value_, int): - raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) - - if field_ == 'rti_phase': - if value_ < 0 or value_ > 2: - raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' - 'take only values 0, 1, 2 for SQP-RTI-type solvers') - if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: - raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' - 'take only value 0 for SQP-type solvers') - - int_value = value_ - acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &int_value) - - elif field_ in double_fields: - if not isinstance(value_, float): - raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) - - double_value = value_ - acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &double_value) - - elif field_ in string_fields: - if not isinstance(value_, bytes): - raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) - - string_value = value_.encode('utf-8') - acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &string_value[0]) - - else: - raise Exception('AcadosOcpSolverCython.options_set() does not support field {}.'\ - '\n Possible values are {}.'.format(field_, ', '.join(int_fields + double_fields + string_fields))) - - - def set_params_sparse(self, int stage, idx_values_, param_values_): - """ - set parameters of the solvers external function partially: - Pseudo: solver.param[idx_values_] = param_values_; - Parameters: - :param stage_: integer corresponding to shooting node - :param idx_values_: 0 based integer array corresponding to parameter indices to be set - :param param_values_: new parameter values as numpy array - """ - - if not isinstance(param_values_, np.ndarray): - raise Exception('param_values_ must be np.array.') - - if param_values_.shape[0] != len(idx_values_): - raise Exception(f'param_values_ and idx_values_ must be of the same size.' + - f' Got sizes idx {param_values_.shape[0]}, param_values {len(idx_values_)}.') - - # n_update = c_int(len(param_values_)) - - # param_data = cast(param_values_.ctypes.data, POINTER(c_double)) - # c_idx_values = np.ascontiguousarray(idx_values_, dtype=np.intc) - # idx_data = cast(c_idx_values.ctypes.data, POINTER(c_int)) - - # getattr(self.shared_lib, f"{self.model_name}_acados_update_params_sparse").argtypes = \ - # [c_void_p, c_int, POINTER(c_int), POINTER(c_double), c_int] - # getattr(self.shared_lib, f"{self.model_name}_acados_update_params_sparse").restype = c_int - # getattr(self.shared_lib, f"{self.model_name}_acados_update_params_sparse") \ - # (self.capsule, stage, idx_data, param_data, n_update) - - cdef cnp.ndarray[cnp.float64_t, ndim=1] value = np.ascontiguousarray(param_values_, dtype=np.float64) - # cdef cnp.ndarray[cnp.intc, ndim=1] idx = np.ascontiguousarray(idx_values_, dtype=np.intc) - - # NOTE: this does throw an error somehow: - # ValueError: Buffer dtype mismatch, expected 'int object' but got 'int' - # cdef cnp.ndarray[cnp.int, ndim=1] idx = np.ascontiguousarray(idx_values_, dtype=np.intc) - - cdef cnp.ndarray[cnp.int32_t, ndim=1] idx = np.ascontiguousarray(idx_values_, dtype=np.int32) - cdef int n_update = value.shape[0] - # print(f"in set_params_sparse Cython n_update {n_update}") - - assert acados_solver.acados_update_params_sparse(self.capsule, stage, idx.data, value.data, n_update) == 0 - return - - - def __del__(self): - if self.solver_created: - acados_solver.acados_free(self.capsule) - acados_solver.acados_free_capsule(self.capsule) diff --git a/third_party/acados/acados_template/acados_sim.py b/third_party/acados/acados_template/acados_sim.py deleted file mode 100644 index 7faa49fb12..0000000000 --- a/third_party/acados/acados_template/acados_sim.py +++ /dev/null @@ -1,366 +0,0 @@ -# -# Copyright (c) The acados authors. -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# - -import numpy as np -import os -from .acados_model import AcadosModel -from .utils import get_acados_path, get_lib_ext - -class AcadosSimDims: - """ - Class containing the dimensions of the model to be simulated. - """ - def __init__(self): - self.__nx = None - self.__nu = None - self.__nz = 0 - self.__np = 0 - - @property - def nx(self): - """:math:`n_x` - number of states. Type: int > 0""" - return self.__nx - - @property - def nz(self): - """:math:`n_z` - number of algebraic variables. Type: int >= 0""" - return self.__nz - - @property - def nu(self): - """:math:`n_u` - number of inputs. Type: int >= 0""" - return self.__nu - - @property - def np(self): - """:math:`n_p` - number of parameters. Type: int >= 0""" - return self.__np - - @nx.setter - def nx(self, nx): - if isinstance(nx, int) and nx > 0: - self.__nx = nx - else: - raise Exception('Invalid nx value, expected positive integer.') - - @nz.setter - def nz(self, nz): - if isinstance(nz, int) and nz > -1: - self.__nz = nz - else: - raise Exception('Invalid nz value, expected nonnegative integer.') - - @nu.setter - def nu(self, nu): - if isinstance(nu, int) and nu > -1: - self.__nu = nu - else: - raise Exception('Invalid nu value, expected nonnegative integer.') - - @np.setter - def np(self, np): - if isinstance(np, int) and np > -1: - self.__np = np - else: - raise Exception('Invalid np value, expected nonnegative integer.') - - def set(self, attr, value): - setattr(self, attr, value) - - -class AcadosSimOpts: - """ - class containing the solver options - """ - def __init__(self): - self.__integrator_type = 'ERK' - self.__collocation_type = 'GAUSS_LEGENDRE' - self.__Tsim = None - # ints - self.__sim_method_num_stages = 1 - self.__sim_method_num_steps = 1 - self.__sim_method_newton_iter = 3 - # doubles - self.__sim_method_newton_tol = 0.0 - # bools - self.__sens_forw = True - self.__sens_adj = False - self.__sens_algebraic = False - self.__sens_hess = False - self.__output_z = True - self.__sim_method_jac_reuse = 0 - self.__ext_fun_compile_flags = '-O2' - - @property - def integrator_type(self): - """Integrator type. Default: 'ERK'.""" - return self.__integrator_type - - @property - def num_stages(self): - """Number of stages in the integrator. Default: 1""" - return self.__sim_method_num_stages - - @property - def num_steps(self): - """Number of steps in the integrator. Default: 1""" - return self.__sim_method_num_steps - - @property - def newton_iter(self): - """Number of Newton iterations in simulation method. Default: 3""" - return self.__sim_method_newton_iter - - @property - def newton_tol(self): - """ - Tolerance for Newton system solved in implicit integrator (IRK, GNSF). - 0.0 means this is not used and exactly newton_iter iterations are carried out. - Default: 0.0 - """ - return self.__sim_method_newton_tol - - @property - def sens_forw(self): - """Boolean determining if forward sensitivities are computed. Default: True""" - return self.__sens_forw - - @property - def sens_adj(self): - """Boolean determining if adjoint sensitivities are computed. Default: False""" - return self.__sens_adj - - @property - def sens_algebraic(self): - """Boolean determining if sensitivities wrt algebraic variables are computed. Default: False""" - return self.__sens_algebraic - - @property - def sens_hess(self): - """Boolean determining if hessians are computed. Default: False""" - return self.__sens_hess - - @property - def output_z(self): - """Boolean determining if values for algebraic variables (corresponding to start of simulation interval) are computed. Default: True""" - return self.__output_z - - @property - def sim_method_jac_reuse(self): - """Integer determining if jacobians are reused (0 or 1). Default: 0""" - return self.__sim_method_jac_reuse - - @property - def T(self): - """Time horizon""" - return self.__Tsim - - @property - def collocation_type(self): - """Collocation type: relevant for implicit integrators - -- string in {GAUSS_RADAU_IIA, GAUSS_LEGENDRE} - - Default: GAUSS_LEGENDRE - """ - return self.__collocation_type - - @property - def ext_fun_compile_flags(self): - """ - String with compiler flags for external function compilation. - Default: '-O2'. - """ - return self.__ext_fun_compile_flags - - @ext_fun_compile_flags.setter - def ext_fun_compile_flags(self, ext_fun_compile_flags): - if isinstance(ext_fun_compile_flags, str): - self.__ext_fun_compile_flags = ext_fun_compile_flags - else: - raise Exception('Invalid ext_fun_compile_flags, expected a string.\n') - - @integrator_type.setter - def integrator_type(self, integrator_type): - integrator_types = ('ERK', 'IRK', 'GNSF') - if integrator_type in integrator_types: - self.__integrator_type = integrator_type - else: - raise Exception('Invalid integrator_type value. Possible values are:\n\n' \ - + ',\n'.join(integrator_types) + '.\n\nYou have: ' + integrator_type + '.\n\n') - - @collocation_type.setter - def collocation_type(self, collocation_type): - collocation_types = ('GAUSS_RADAU_IIA', 'GAUSS_LEGENDRE') - if collocation_type in collocation_types: - self.__collocation_type = collocation_type - else: - raise Exception('Invalid collocation_type value. Possible values are:\n\n' \ - + ',\n'.join(collocation_types) + '.\n\nYou have: ' + collocation_type + '.\n\n') - - @T.setter - def T(self, T): - self.__Tsim = T - - @num_stages.setter - def num_stages(self, num_stages): - if isinstance(num_stages, int): - self.__sim_method_num_stages = num_stages - else: - raise Exception('Invalid num_stages value. num_stages must be an integer.') - - @num_steps.setter - def num_steps(self, num_steps): - if isinstance(num_steps, int): - self.__sim_method_num_steps = num_steps - else: - raise Exception('Invalid num_steps value. num_steps must be an integer.') - - @newton_iter.setter - def newton_iter(self, newton_iter): - if isinstance(newton_iter, int): - self.__sim_method_newton_iter = newton_iter - else: - raise Exception('Invalid newton_iter value. newton_iter must be an integer.') - - @newton_tol.setter - def newton_tol(self, newton_tol): - if isinstance(newton_tol, float): - self.__sim_method_newton_tol = newton_tol - else: - raise Exception('Invalid newton_tol value. newton_tol must be an float.') - - @sens_forw.setter - def sens_forw(self, sens_forw): - if sens_forw in (True, False): - self.__sens_forw = sens_forw - else: - raise Exception('Invalid sens_forw value. sens_forw must be a Boolean.') - - @sens_adj.setter - def sens_adj(self, sens_adj): - if sens_adj in (True, False): - self.__sens_adj = sens_adj - else: - raise Exception('Invalid sens_adj value. sens_adj must be a Boolean.') - - @sens_hess.setter - def sens_hess(self, sens_hess): - if sens_hess in (True, False): - self.__sens_hess = sens_hess - else: - raise Exception('Invalid sens_hess value. sens_hess must be a Boolean.') - - @sens_algebraic.setter - def sens_algebraic(self, sens_algebraic): - if sens_algebraic in (True, False): - self.__sens_algebraic = sens_algebraic - else: - raise Exception('Invalid sens_algebraic value. sens_algebraic must be a Boolean.') - - @output_z.setter - def output_z(self, output_z): - if output_z in (True, False): - self.__output_z = output_z - else: - raise Exception('Invalid output_z value. output_z must be a Boolean.') - - @sim_method_jac_reuse.setter - def sim_method_jac_reuse(self, sim_method_jac_reuse): - if sim_method_jac_reuse in (0, 1): - self.__sim_method_jac_reuse = sim_method_jac_reuse - else: - raise Exception('Invalid sim_method_jac_reuse value. sim_method_jac_reuse must be 0 or 1.') - -class AcadosSim: - """ - The class has the following properties that can be modified to formulate a specific simulation problem, see below: - - :param acados_path: string with the path to acados. It is used to generate the include and lib paths. - - - :py:attr:`dims` of type :py:class:`acados_template.acados_ocp.AcadosSimDims` - are automatically detected from model - - :py:attr:`model` of type :py:class:`acados_template.acados_model.AcadosModel` - - :py:attr:`solver_options` of type :py:class:`acados_template.acados_sim.AcadosSimOpts` - - - :py:attr:`acados_include_path` (set automatically) - - :py:attr:`shared_lib_ext` (set automatically) - - :py:attr:`acados_lib_path` (set automatically) - - :py:attr:`parameter_values` - used to initialize the parameters (can be changed) - - """ - def __init__(self, acados_path=''): - if acados_path == '': - acados_path = get_acados_path() - self.dims = AcadosSimDims() - """Dimension definitions, automatically detected from :py:attr:`model`. Type :py:class:`acados_template.acados_sim.AcadosSimDims`""" - self.model = AcadosModel() - """Model definitions, type :py:class:`acados_template.acados_model.AcadosModel`""" - self.solver_options = AcadosSimOpts() - """Solver Options, type :py:class:`acados_template.acados_sim.AcadosSimOpts`""" - - self.acados_include_path = os.path.join(acados_path, 'include').replace(os.sep, '/') # the replace part is important on Windows for CMake - """Path to acados include directory (set automatically), type: `string`""" - self.acados_lib_path = os.path.join(acados_path, 'lib').replace(os.sep, '/') # the replace part is important on Windows for CMake - """Path to where acados library is located (set automatically), type: `string`""" - - self.code_export_directory = 'c_generated_code' - """Path to where code will be exported. Default: `c_generated_code`.""" - self.shared_lib_ext = get_lib_ext() - - # get cython paths - from sysconfig import get_paths - self.cython_include_dirs = [np.get_include(), get_paths()['include']] - - self.__parameter_values = np.array([]) - self.__problem_class = 'SIM' - - @property - def parameter_values(self): - """:math:`p` - initial values for parameter - can be updated""" - return self.__parameter_values - - @parameter_values.setter - def parameter_values(self, parameter_values): - if isinstance(parameter_values, np.ndarray): - self.__parameter_values = parameter_values - else: - raise Exception('Invalid parameter_values value. ' + - f'Expected numpy array, got {type(parameter_values)}.') - - def set(self, attr, value): - # tokenize string - tokens = attr.split('_', 1) - if len(tokens) > 1: - setter_to_call = getattr(getattr(self, tokens[0]), 'set') - else: - setter_to_call = getattr(self, 'set') - - setter_to_call(tokens[1], value) - - return diff --git a/third_party/acados/acados_template/acados_sim_layout.json b/third_party/acados/acados_template/acados_sim_layout.json deleted file mode 100644 index e3ca4b575b..0000000000 --- a/third_party/acados/acados_template/acados_sim_layout.json +++ /dev/null @@ -1,53 +0,0 @@ -{ - "acados_include_path": [ - "str" - ], - "model": { - "name" : [ - "str" - ] - }, - "acados_lib_path": [ - "str" - ], - "dims": { - "np": [ - "int" - ], - "nu": [ - "int" - ], - "nx": [ - "int" - ], - "nz": [ - "int" - ] - }, - "solver_options": { - "integrator_type": [ - "str" - ], - "collocation_type": [ - "str" - ], - "Tsim": [ - "float" - ], - "sim_method_num_stages": [ - "int" - ], - "sim_method_num_steps": [ - "int" - ], - "sim_method_newton_iter": [ - "int" - ], - "sim_method_newton_tol": [ - "float" - ], - "ext_fun_compile_flags": [ - "str" - ] - } -} diff --git a/third_party/acados/acados_template/acados_sim_solver.py b/third_party/acados/acados_template/acados_sim_solver.py deleted file mode 100644 index de5ee10709..0000000000 --- a/third_party/acados/acados_template/acados_sim_solver.py +++ /dev/null @@ -1,558 +0,0 @@ -# -# Copyright (c) The acados authors. -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# - -import sys -import os -import json -import importlib - -import numpy as np - -from subprocess import DEVNULL, call, STDOUT - -from ctypes import POINTER, cast, CDLL, c_void_p, c_char_p, c_double, c_int, c_bool, byref -from copy import deepcopy - -from .casadi_function_generation import generate_c_code_implicit_ode, generate_c_code_gnsf, generate_c_code_explicit_ode -from .acados_sim import AcadosSim -from .acados_ocp import AcadosOcp -from .utils import is_column, render_template, format_class_dict, make_object_json_dumpable,\ - make_model_consistent, set_up_imported_gnsf_model, get_python_interface_path, get_lib_ext,\ - casadi_length, is_empty, check_casadi_version -from .builders import CMakeBuilder -from .gnsf.detect_gnsf_structure import detect_gnsf_structure - - - -def make_sim_dims_consistent(acados_sim: AcadosSim): - dims = acados_sim.dims - model = acados_sim.model - # nx - if is_column(model.x): - dims.nx = casadi_length(model.x) - else: - raise Exception('model.x should be column vector!') - - # nu - if is_empty(model.u): - dims.nu = 0 - else: - dims.nu = casadi_length(model.u) - - # nz - if is_empty(model.z): - dims.nz = 0 - else: - dims.nz = casadi_length(model.z) - - # np - if is_empty(model.p): - dims.np = 0 - else: - dims.np = casadi_length(model.p) - if acados_sim.parameter_values.shape[0] != dims.np: - raise Exception('inconsistent dimension np, regarding model.p and parameter_values.' + \ - f'\nGot np = {dims.np}, acados_sim.parameter_values.shape = {acados_sim.parameter_values.shape[0]}\n') - - -def get_sim_layout(): - python_interface_path = get_python_interface_path() - abs_path = os.path.join(python_interface_path, 'acados_sim_layout.json') - with open(abs_path, 'r') as f: - sim_layout = json.load(f) - return sim_layout - - -def sim_formulation_json_dump(acados_sim: AcadosSim, json_file='acados_sim.json'): - # Load acados_sim structure description - sim_layout = get_sim_layout() - - # Copy input sim object dictionary - sim_dict = dict(deepcopy(acados_sim).__dict__) - - for key, v in sim_layout.items(): - # skip non dict attributes - if not isinstance(v, dict): continue - # Copy sim object attributes dictionaries - sim_dict[key]=dict(getattr(acados_sim, key).__dict__) - - sim_json = format_class_dict(sim_dict) - - with open(json_file, 'w') as f: - json.dump(sim_json, f, default=make_object_json_dumpable, indent=4, sort_keys=True) - - -def sim_get_default_cmake_builder() -> CMakeBuilder: - """ - If :py:class:`~acados_template.acados_sim_solver.AcadosSimSolver` is used with `CMake` this function returns a good first setting. - :return: default :py:class:`~acados_template.builders.CMakeBuilder` - """ - cmake_builder = CMakeBuilder() - cmake_builder.options_on = ['BUILD_ACADOS_SIM_SOLVER_LIB'] - return cmake_builder - - -def sim_render_templates(json_file, model_name: str, code_export_dir, cmake_options: CMakeBuilder = None): - # setting up loader and environment - json_path = os.path.join(os.getcwd(), json_file) - - if not os.path.exists(json_path): - raise Exception(f"{json_path} not found!") - - # Render templates - in_file = 'acados_sim_solver.in.c' - out_file = f'acados_sim_solver_{model_name}.c' - render_template(in_file, out_file, code_export_dir, json_path) - - in_file = 'acados_sim_solver.in.h' - out_file = f'acados_sim_solver_{model_name}.h' - render_template(in_file, out_file, code_export_dir, json_path) - - in_file = 'acados_sim_solver.in.pxd' - out_file = f'acados_sim_solver.pxd' - render_template(in_file, out_file, code_export_dir, json_path) - - # Builder - if cmake_options is not None: - in_file = 'CMakeLists.in.txt' - out_file = 'CMakeLists.txt' - render_template(in_file, out_file, code_export_dir, json_path) - else: - in_file = 'Makefile.in' - out_file = 'Makefile' - render_template(in_file, out_file, code_export_dir, json_path) - - in_file = 'main_sim.in.c' - out_file = f'main_sim_{model_name}.c' - render_template(in_file, out_file, code_export_dir, json_path) - - # folder model - model_dir = os.path.join(code_export_dir, model_name + '_model') - - in_file = 'model.in.h' - out_file = f'{model_name}_model.h' - render_template(in_file, out_file, model_dir, json_path) - - -def sim_generate_external_functions(acados_sim: AcadosSim): - model = acados_sim.model - model = make_model_consistent(model) - - integrator_type = acados_sim.solver_options.integrator_type - - opts = dict(generate_hess = acados_sim.solver_options.sens_hess, - code_export_directory = acados_sim.code_export_directory) - - # create code_export_dir, model_dir - code_export_dir = acados_sim.code_export_directory - opts['code_export_directory'] = code_export_dir - model_dir = os.path.join(code_export_dir, model.name + '_model') - if not os.path.exists(model_dir): - os.makedirs(model_dir) - - # generate external functions - check_casadi_version() - if integrator_type == 'ERK': - generate_c_code_explicit_ode(model, opts) - elif integrator_type == 'IRK': - generate_c_code_implicit_ode(model, opts) - elif integrator_type == 'GNSF': - generate_c_code_gnsf(model, opts) - - -class AcadosSimSolver: - """ - Class to interact with the acados integrator C object. - - :param acados_sim: type :py:class:`~acados_template.acados_ocp.AcadosOcp` (takes values to generate an instance :py:class:`~acados_template.acados_sim.AcadosSim`) or :py:class:`~acados_template.acados_sim.AcadosSim` - :param json_file: Default: 'acados_sim.json' - :param build: Default: True - :param cmake_builder: type :py:class:`~acados_template.utils.CMakeBuilder` generate a `CMakeLists.txt` and use - the `CMake` pipeline instead of a `Makefile` (`CMake` seems to be the better option in conjunction with - `MS Visual Studio`); default: `None` - """ - if sys.platform=="win32": - from ctypes import wintypes - from ctypes import WinDLL - dlclose = WinDLL('kernel32', use_last_error=True).FreeLibrary - dlclose.argtypes = [wintypes.HMODULE] - else: - dlclose = CDLL(None).dlclose - dlclose.argtypes = [c_void_p] - - - @classmethod - def generate(cls, acados_sim: AcadosSim, json_file='acados_sim.json', cmake_builder: CMakeBuilder = None): - """ - Generates the code for an acados sim solver, given the description in acados_sim - """ - - acados_sim.code_export_directory = os.path.abspath(acados_sim.code_export_directory) - - # make dims consistent - make_sim_dims_consistent(acados_sim) - - # module dependent post processing - if acados_sim.solver_options.integrator_type == 'GNSF': - if acados_sim.solver_options.sens_hess == True: - raise Exception("AcadosSimSolver: GNSF does not support sens_hess = True.") - if 'gnsf_model' in acados_sim.__dict__: - set_up_imported_gnsf_model(acados_sim) - else: - detect_gnsf_structure(acados_sim) - - # generate external functions - sim_generate_external_functions(acados_sim) - - # dump to json - sim_formulation_json_dump(acados_sim, json_file) - - # render templates - sim_render_templates(json_file, acados_sim.model.name, acados_sim.code_export_directory, cmake_builder) - - - @classmethod - def build(cls, code_export_dir, with_cython=False, cmake_builder: CMakeBuilder = None, verbose: bool = True): - # Compile solver - cwd = os.getcwd() - os.chdir(code_export_dir) - if with_cython: - call( - ['make', 'clean_sim_cython'], - stdout=None if verbose else DEVNULL, - stderr=None if verbose else STDOUT - ) - call( - ['make', 'sim_cython'], - stdout=None if verbose else DEVNULL, - stderr=None if verbose else STDOUT - ) - else: - if cmake_builder is not None: - cmake_builder.exec(code_export_dir, verbose=verbose) - else: - call( - ['make', 'sim_shared_lib'], - stdout=None if verbose else DEVNULL, - stderr=None if verbose else STDOUT - ) - os.chdir(cwd) - - - @classmethod - def create_cython_solver(cls, json_file): - """ - """ - with open(json_file, 'r') as f: - acados_sim_json = json.load(f) - code_export_directory = acados_sim_json['code_export_directory'] - - importlib.invalidate_caches() - rel_code_export_directory = os.path.relpath(code_export_directory) - acados_sim_solver_pyx = importlib.import_module(f'{rel_code_export_directory}.acados_sim_solver_pyx') - - AcadosSimSolverCython = getattr(acados_sim_solver_pyx, 'AcadosSimSolverCython') - return AcadosSimSolverCython(acados_sim_json['model']['name']) - - def __init__(self, acados_sim, json_file='acados_sim.json', generate=True, build=True, cmake_builder: CMakeBuilder = None, verbose: bool = True): - - self.solver_created = False - self.acados_sim = acados_sim - model_name = acados_sim.model.name - self.model_name = model_name - - code_export_dir = os.path.abspath(acados_sim.code_export_directory) - - # reuse existing json and casadi functions, when creating integrator from ocp - if generate and not isinstance(acados_sim, AcadosOcp): - self.generate(acados_sim, json_file=json_file, cmake_builder=cmake_builder) - - if build: - self.build(code_export_dir, cmake_builder=cmake_builder, verbose=True) - - # prepare library loading - lib_prefix = 'lib' - lib_ext = get_lib_ext() - if os.name == 'nt': - lib_prefix = '' - - # Load acados library to avoid unloading the library. - # This is necessary if acados was compiled with OpenMP, since the OpenMP threads can't be destroyed. - # Unloading a library which uses OpenMP results in a segfault (on any platform?). - # see [https://stackoverflow.com/questions/34439956/vc-crash-when-freeing-a-dll-built-with-openmp] - # or [https://python.hotexamples.com/examples/_ctypes/-/dlclose/python-dlclose-function-examples.html] - libacados_name = f'{lib_prefix}acados{lib_ext}' - libacados_filepath = os.path.join(acados_sim.acados_lib_path, libacados_name) - self.__acados_lib = CDLL(libacados_filepath) - # find out if acados was compiled with OpenMP - try: - self.__acados_lib_uses_omp = getattr(self.__acados_lib, 'omp_get_thread_num') is not None - except AttributeError as e: - self.__acados_lib_uses_omp = False - if self.__acados_lib_uses_omp: - print('acados was compiled with OpenMP.') - else: - print('acados was compiled without OpenMP.') - libacados_sim_solver_name = f'{lib_prefix}acados_sim_solver_{self.model_name}{lib_ext}' - self.shared_lib_name = os.path.join(code_export_dir, libacados_sim_solver_name) - - # get shared_lib - self.shared_lib = CDLL(self.shared_lib_name) - - # create capsule - getattr(self.shared_lib, f"{model_name}_acados_sim_solver_create_capsule").restype = c_void_p - self.capsule = getattr(self.shared_lib, f"{model_name}_acados_sim_solver_create_capsule")() - - # create solver - getattr(self.shared_lib, f"{model_name}_acados_sim_create").argtypes = [c_void_p] - getattr(self.shared_lib, f"{model_name}_acados_sim_create").restype = c_int - assert getattr(self.shared_lib, f"{model_name}_acados_sim_create")(self.capsule)==0 - self.solver_created = True - - getattr(self.shared_lib, f"{model_name}_acados_get_sim_opts").argtypes = [c_void_p] - getattr(self.shared_lib, f"{model_name}_acados_get_sim_opts").restype = c_void_p - self.sim_opts = getattr(self.shared_lib, f"{model_name}_acados_get_sim_opts")(self.capsule) - - getattr(self.shared_lib, f"{model_name}_acados_get_sim_dims").argtypes = [c_void_p] - getattr(self.shared_lib, f"{model_name}_acados_get_sim_dims").restype = c_void_p - self.sim_dims = getattr(self.shared_lib, f"{model_name}_acados_get_sim_dims")(self.capsule) - - getattr(self.shared_lib, f"{model_name}_acados_get_sim_config").argtypes = [c_void_p] - getattr(self.shared_lib, f"{model_name}_acados_get_sim_config").restype = c_void_p - self.sim_config = getattr(self.shared_lib, f"{model_name}_acados_get_sim_config")(self.capsule) - - getattr(self.shared_lib, f"{model_name}_acados_get_sim_out").argtypes = [c_void_p] - getattr(self.shared_lib, f"{model_name}_acados_get_sim_out").restype = c_void_p - self.sim_out = getattr(self.shared_lib, f"{model_name}_acados_get_sim_out")(self.capsule) - - getattr(self.shared_lib, f"{model_name}_acados_get_sim_in").argtypes = [c_void_p] - getattr(self.shared_lib, f"{model_name}_acados_get_sim_in").restype = c_void_p - self.sim_in = getattr(self.shared_lib, f"{model_name}_acados_get_sim_in")(self.capsule) - - getattr(self.shared_lib, f"{model_name}_acados_get_sim_solver").argtypes = [c_void_p] - getattr(self.shared_lib, f"{model_name}_acados_get_sim_solver").restype = c_void_p - self.sim_solver = getattr(self.shared_lib, f"{model_name}_acados_get_sim_solver")(self.capsule) - - self.gettable_vectors = ['x', 'u', 'z', 'S_adj'] - self.gettable_matrices = ['S_forw', 'Sx', 'Su', 'S_hess', 'S_algebraic'] - self.gettable_scalars = ['CPUtime', 'time_tot', 'ADtime', 'time_ad', 'LAtime', 'time_la'] - - - def simulate(self, x=None, u=None, z=None, p=None): - """ - Simulate the system forward for the given x, u, z, p and return x_next. - Wrapper around `solve()` taking care of setting/getting inputs/outputs. - """ - if x is not None: - self.set('x', x) - if u is not None: - self.set('u', u) - if z is not None: - self.set('z', z) - if p is not None: - self.set('p', p) - - status = self.solve() - - if status == 2: - print("Warning: acados_sim_solver reached maximum iterations.") - elif status != 0: - raise Exception(f'acados_sim_solver for model {self.model_name} returned status {status}.') - - x_next = self.get('x') - return x_next - - - def solve(self): - """ - Solve the simulation problem with current input. - """ - getattr(self.shared_lib, f"{self.model_name}_acados_sim_solve").argtypes = [c_void_p] - getattr(self.shared_lib, f"{self.model_name}_acados_sim_solve").restype = c_int - - status = getattr(self.shared_lib, f"{self.model_name}_acados_sim_solve")(self.capsule) - return status - - - def get(self, field_): - """ - Get the last solution of the solver. - - :param str field: string in ['x', 'u', 'z', 'S_forw', 'Sx', 'Su', 'S_adj', 'S_hess', 'S_algebraic', 'CPUtime', 'time_tot', 'ADtime', 'time_ad', 'LAtime', 'time_la'] - """ - field = field_.encode('utf-8') - - if field_ in self.gettable_vectors: - # get dims - dims = np.ascontiguousarray(np.zeros((2,)), dtype=np.intc) - dims_data = cast(dims.ctypes.data, POINTER(c_int)) - - self.shared_lib.sim_dims_get_from_attr.argtypes = [c_void_p, c_void_p, c_char_p, POINTER(c_int)] - self.shared_lib.sim_dims_get_from_attr(self.sim_config, self.sim_dims, field, dims_data) - - # allocate array - out = np.ascontiguousarray(np.zeros((dims[0],)), dtype=np.float64) - out_data = cast(out.ctypes.data, POINTER(c_double)) - - self.shared_lib.sim_out_get.argtypes = [c_void_p, c_void_p, c_void_p, c_char_p, c_void_p] - self.shared_lib.sim_out_get(self.sim_config, self.sim_dims, self.sim_out, field, out_data) - - elif field_ in self.gettable_matrices: - # get dims - dims = np.ascontiguousarray(np.zeros((2,)), dtype=np.intc) - dims_data = cast(dims.ctypes.data, POINTER(c_int)) - - self.shared_lib.sim_dims_get_from_attr.argtypes = [c_void_p, c_void_p, c_char_p, POINTER(c_int)] - self.shared_lib.sim_dims_get_from_attr(self.sim_config, self.sim_dims, field, dims_data) - - out = np.zeros((dims[0], dims[1]), order='F') - out_data = cast(out.ctypes.data, POINTER(c_double)) - - self.shared_lib.sim_out_get.argtypes = [c_void_p, c_void_p, c_void_p, c_char_p, c_void_p] - self.shared_lib.sim_out_get(self.sim_config, self.sim_dims, self.sim_out, field, out_data) - - elif field_ in self.gettable_scalars: - scalar = c_double() - scalar_data = byref(scalar) - self.shared_lib.sim_out_get.argtypes = [c_void_p, c_void_p, c_void_p, c_char_p, c_void_p] - self.shared_lib.sim_out_get(self.sim_config, self.sim_dims, self.sim_out, field, scalar_data) - - out = scalar.value - else: - raise Exception(f'AcadosSimSolver.get(): Unknown field {field_},' \ - f' available fields are {", ".join(self.gettable_vectors+self.gettable_matrices)}, {", ".join(self.gettable_scalars)}') - - return out - - - - def set(self, field_: str, value_): - """ - Set numerical data inside the solver. - - :param field: string in ['x', 'u', 'p', 'xdot', 'z', 'seed_adj', 'T'] - :param value: the value with appropriate size. - """ - settable = ['x', 'u', 'p', 'xdot', 'z', 'seed_adj', 'T'] # S_forw - - # TODO: check and throw error here. then remove checks in Cython for speed - # cast value_ to avoid conversion issues - if isinstance(value_, (float, int)): - value_ = np.array([value_]) - - value_ = value_.astype(float) - value_data = cast(value_.ctypes.data, POINTER(c_double)) - value_data_p = cast((value_data), c_void_p) - - field = field_.encode('utf-8') - - # treat parameters separately - if field_ == 'p': - model_name = self.acados_sim.model.name - getattr(self.shared_lib, f"{model_name}_acados_sim_update_params").argtypes = [c_void_p, POINTER(c_double), c_int] - value_data = cast(value_.ctypes.data, POINTER(c_double)) - getattr(self.shared_lib, f"{model_name}_acados_sim_update_params")(self.capsule, value_data, value_.shape[0]) - return - else: - # dimension check - dims = np.ascontiguousarray(np.zeros((2,)), dtype=np.intc) - dims_data = cast(dims.ctypes.data, POINTER(c_int)) - - self.shared_lib.sim_dims_get_from_attr.argtypes = [c_void_p, c_void_p, c_char_p, POINTER(c_int)] - self.shared_lib.sim_dims_get_from_attr(self.sim_config, self.sim_dims, field, dims_data) - - value_ = np.ravel(value_, order='F') - - value_shape = value_.shape - if len(value_shape) == 1: - value_shape = (value_shape[0], 0) - - if value_shape != tuple(dims): - raise Exception(f'AcadosSimSolver.set(): mismatching dimension' \ - f' for field "{field_}" with dimension {tuple(dims)} (you have {value_shape}).') - - # set - if field_ in ['xdot', 'z']: - self.shared_lib.sim_solver_set.argtypes = [c_void_p, c_char_p, c_void_p] - self.shared_lib.sim_solver_set(self.sim_solver, field, value_data_p) - elif field_ in settable: - self.shared_lib.sim_in_set.argtypes = [c_void_p, c_void_p, c_void_p, c_char_p, c_void_p] - self.shared_lib.sim_in_set(self.sim_config, self.sim_dims, self.sim_in, field, value_data_p) - else: - raise Exception(f'AcadosSimSolver.set(): Unknown field {field_},' \ - f' available fields are {", ".join(settable)}') - - return - - - def options_set(self, field_: str, value_: bool): - """ - Set solver options - - :param field: string in ['sens_forw', 'sens_adj', 'sens_hess'] - :param value: Boolean - """ - fields = ['sens_forw', 'sens_adj', 'sens_hess'] - if field_ not in fields: - raise Exception(f"field {field_} not supported. Supported values are {', '.join(fields)}.\n") - - field = field_.encode('utf-8') - value_ctypes = c_bool(value_) - - if not isinstance(value_, bool): - raise TypeError("options_set: expected boolean for value") - - # only allow setting - if getattr(self.acados_sim.solver_options, field_) or value_ == False: - self.shared_lib.sim_opts_set.argtypes = [c_void_p, c_void_p, c_char_p, POINTER(c_bool)] - self.shared_lib.sim_opts_set(self.sim_config, self.sim_opts, field, value_ctypes) - else: - raise RuntimeError(f"Cannot set option {field_} to True, because it was False in original solver options.\n") - - return - - - def __del__(self): - - if self.solver_created: - getattr(self.shared_lib, f"{self.model_name}_acados_sim_free").argtypes = [c_void_p] - getattr(self.shared_lib, f"{self.model_name}_acados_sim_free").restype = c_int - getattr(self.shared_lib, f"{self.model_name}_acados_sim_free")(self.capsule) - - getattr(self.shared_lib, f"{self.model_name}_acados_sim_solver_free_capsule").argtypes = [c_void_p] - getattr(self.shared_lib, f"{self.model_name}_acados_sim_solver_free_capsule").restype = c_int - getattr(self.shared_lib, f"{self.model_name}_acados_sim_solver_free_capsule")(self.capsule) - - try: - self.dlclose(self.shared_lib._handle) - except: - print(f"WARNING: acados Python interface could not close shared_lib handle of AcadosSimSolver {self.model_name}.\n", - "Attempting to create a new one with the same name will likely result in the old one being used!") - pass diff --git a/third_party/acados/acados_template/acados_sim_solver_common.pxd b/third_party/acados/acados_template/acados_sim_solver_common.pxd deleted file mode 100644 index 7c20a6d24d..0000000000 --- a/third_party/acados/acados_template/acados_sim_solver_common.pxd +++ /dev/null @@ -1,63 +0,0 @@ -# -# Copyright (c) The acados authors. -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# - - -cdef extern from "acados/sim/sim_common.h": - ctypedef struct sim_config: - pass - - ctypedef struct sim_opts: - pass - - ctypedef struct sim_in: - pass - - ctypedef struct sim_out: - pass - - -cdef extern from "acados_c/sim_interface.h": - - ctypedef struct sim_plan: - pass - - ctypedef struct sim_solver: - pass - - # out - void sim_out_get(sim_config *config, void *dims, sim_out *out, const char *field, void *value) - int sim_dims_get_from_attr(sim_config *config, void *dims, const char *field, void *dims_data) - - # opts - void sim_opts_set(sim_config *config, void *opts_, const char *field, void *value) - - # get/set - void sim_in_set(sim_config *config, void *dims, sim_in *sim_in, const char *field, void *value) - void sim_solver_set(sim_solver *solver, const char *field, void *value) \ No newline at end of file diff --git a/third_party/acados/acados_template/acados_sim_solver_pyx.pyx b/third_party/acados/acados_template/acados_sim_solver_pyx.pyx deleted file mode 100644 index 01964fd7a0..0000000000 --- a/third_party/acados/acados_template/acados_sim_solver_pyx.pyx +++ /dev/null @@ -1,255 +0,0 @@ -# -# Copyright (c) The acados authors. -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# -# cython: language_level=3 -# cython: profile=False -# distutils: language=c - -cimport cython -from libc cimport string -# from libc cimport bool as bool_t - -cimport acados_sim_solver_common -cimport acados_sim_solver - -cimport numpy as cnp - -import os -from datetime import datetime -import numpy as np - - -cdef class AcadosSimSolverCython: - """ - Class to interact with the acados sim solver C object. - """ - - cdef acados_sim_solver.sim_solver_capsule *capsule - cdef void *sim_dims - cdef acados_sim_solver_common.sim_opts *sim_opts - cdef acados_sim_solver_common.sim_config *sim_config - cdef acados_sim_solver_common.sim_out *sim_out - cdef acados_sim_solver_common.sim_in *sim_in - cdef acados_sim_solver_common.sim_solver *sim_solver - - cdef bint solver_created - - cdef str model_name - - cdef str sim_solver_type - - cdef list gettable_vectors - cdef list gettable_matrices - cdef list gettable_scalars - - def __cinit__(self, model_name): - - self.solver_created = False - - self.model_name = model_name - - # create capsule - self.capsule = acados_sim_solver.acados_sim_solver_create_capsule() - - # create solver - assert acados_sim_solver.acados_sim_create(self.capsule) == 0 - self.solver_created = True - - # get pointers solver - self.__get_pointers_solver() - - self.gettable_vectors = ['x', 'u', 'z', 'S_adj'] - self.gettable_matrices = ['S_forw', 'Sx', 'Su', 'S_hess', 'S_algebraic'] - self.gettable_scalars = ['CPUtime', 'time_tot', 'ADtime', 'time_ad', 'LAtime', 'time_la'] - - def __get_pointers_solver(self): - """ - Private function to get the pointers for solver - """ - # get pointers solver - self.sim_opts = acados_sim_solver.acados_get_sim_opts(self.capsule) - self.sim_dims = acados_sim_solver.acados_get_sim_dims(self.capsule) - self.sim_config = acados_sim_solver.acados_get_sim_config(self.capsule) - self.sim_out = acados_sim_solver.acados_get_sim_out(self.capsule) - self.sim_in = acados_sim_solver.acados_get_sim_in(self.capsule) - self.sim_solver = acados_sim_solver.acados_get_sim_solver(self.capsule) - - - def simulate(self, x=None, u=None, z=None, p=None): - """ - Simulate the system forward for the given x, u, z, p and return x_next. - Wrapper around `solve()` taking care of setting/getting inputs/outputs. - """ - if x is not None: - self.set('x', x) - if u is not None: - self.set('u', u) - if z is not None: - self.set('z', z) - if p is not None: - self.set('p', p) - - status = self.solve() - - if status == 2: - print("Warning: acados_sim_solver reached maximum iterations.") - elif status != 0: - raise Exception(f'acados_sim_solver for model {self.model_name} returned status {status}.') - - x_next = self.get('x') - return x_next - - - def solve(self): - """ - Solve the sim with current input. - """ - return acados_sim_solver.acados_sim_solve(self.capsule) - - - def get(self, field_): - """ - Get the last solution of the solver. - - :param str field: string in ['x', 'u', 'z', 'S_forw', 'Sx', 'Su', 'S_adj', 'S_hess', 'S_algebraic', 'CPUtime', 'time_tot', 'ADtime', 'time_ad', 'LAtime', 'time_la'] - """ - field = field_.encode('utf-8') - - if field_ in self.gettable_vectors: - return self.__get_vector(field) - elif field_ in self.gettable_matrices: - return self.__get_matrix(field) - elif field_ in self.gettable_scalars: - return self.__get_scalar(field) - else: - raise Exception(f'AcadosSimSolver.get(): Unknown field {field_},' \ - f' available fields are {", ".join(self.gettable.keys())}') - - - def __get_scalar(self, field): - cdef double scalar - acados_sim_solver_common.sim_out_get(self.sim_config, self.sim_dims, self.sim_out, field, &scalar) - return scalar - - - def __get_vector(self, field): - cdef int[2] dims - acados_sim_solver_common.sim_dims_get_from_attr(self.sim_config, self.sim_dims, field, &dims[0]) - # cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.ascontiguousarray(np.zeros((dims[0],), dtype=np.float64)) - cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((dims[0]),) - acados_sim_solver_common.sim_out_get(self.sim_config, self.sim_dims, self.sim_out, field, out.data) - return out - - - def __get_matrix(self, field): - cdef int[2] dims - acados_sim_solver_common.sim_dims_get_from_attr(self.sim_config, self.sim_dims, field, &dims[0]) - cdef cnp.ndarray[cnp.float64_t, ndim=2] out = np.zeros((dims[0], dims[1]), order='F', dtype=np.float64) - acados_sim_solver_common.sim_out_get(self.sim_config, self.sim_dims, self.sim_out, field, out.data) - return out - - - def set(self, field_: str, value_): - """ - Set numerical data inside the solver. - - :param field: string in ['p', 'seed_adj', 'T', 'x', 'u', 'xdot', 'z'] - :param value: the value with appropriate size. - """ - settable = ['seed_adj', 'T', 'x', 'u', 'xdot', 'z', 'p'] # S_forw - - # cast value_ to avoid conversion issues - if isinstance(value_, (float, int)): - value_ = np.array([value_]) - # if len(value_.shape) > 1: - # raise RuntimeError('AcadosSimSolverCython.set(): value_ should be 1 dimensional') - - cdef cnp.ndarray[cnp.float64_t, ndim=1] value = np.ascontiguousarray(value_, dtype=np.float64).flatten() - - field = field_.encode('utf-8') - cdef int[2] dims - - # treat parameters separately - if field_ == 'p': - assert acados_sim_solver.acados_sim_update_params(self.capsule, value.data, value.shape[0]) == 0 - return - else: - acados_sim_solver_common.sim_dims_get_from_attr(self.sim_config, self.sim_dims, field, &dims[0]) - - value_ = np.ravel(value_, order='F') - - value_shape = value_.shape - if len(value_shape) == 1: - value_shape = (value_shape[0], 0) - - if value_shape != tuple(dims): - raise Exception(f'AcadosSimSolverCython.set(): mismatching dimension' \ - f' for field "{field_}" with dimension {tuple(dims)} (you have {value_shape}).') - - # set - if field_ in ['xdot', 'z']: - acados_sim_solver_common.sim_solver_set(self.sim_solver, field, value.data) - elif field_ in settable: - acados_sim_solver_common.sim_in_set(self.sim_config, self.sim_dims, self.sim_in, field, value.data) - else: - raise Exception(f'AcadosSimSolverCython.set(): Unknown field {field_},' \ - f' available fields are {", ".join(settable)}') - - - def options_set(self, field_: str, value_: bool): - """ - Set solver options - - :param field: string in ['sens_forw', 'sens_adj', 'sens_hess'] - :param value: Boolean - """ - fields = ['sens_forw', 'sens_adj', 'sens_hess'] - if field_ not in fields: - raise Exception(f"field {field_} not supported. Supported values are {', '.join(fields)}.\n") - - field = field_.encode('utf-8') - - if not isinstance(value_, bool): - raise TypeError("options_set: expected boolean for value") - - cdef bint bool_value = value_ - acados_sim_solver_common.sim_opts_set(self.sim_config, self.sim_opts, field, &bool_value) - # TODO: only allow setting - # if getattr(self.acados_sim.solver_options, field_) or value_ == False: - # acados_sim_solver_common.sim_opts_set(self.sim_config, self.sim_opts, field, &bool_value) - # else: - # raise RuntimeError(f"Cannot set option {field_} to True, because it was False in original solver options.\n") - - return - - - def __del__(self): - if self.solver_created: - acados_sim_solver.acados_sim_free(self.capsule) - acados_sim_solver.acados_sim_solver_free_capsule(self.capsule) diff --git a/third_party/acados/acados_template/acados_solver_common.pxd b/third_party/acados/acados_template/acados_solver_common.pxd deleted file mode 100644 index 75d021626f..0000000000 --- a/third_party/acados/acados_template/acados_solver_common.pxd +++ /dev/null @@ -1,99 +0,0 @@ -# -# Copyright (c) The acados authors. -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# - - -cdef extern from "acados/ocp_nlp/ocp_nlp_common.h": - ctypedef struct ocp_nlp_config: - pass - - ctypedef struct ocp_nlp_dims: - pass - - ctypedef struct ocp_nlp_in: - pass - - ctypedef struct ocp_nlp_out: - pass - - -cdef extern from "acados_c/ocp_nlp_interface.h": - ctypedef enum ocp_nlp_solver_t: - pass - - ctypedef enum ocp_nlp_cost_t: - pass - - ctypedef enum ocp_nlp_dynamics_t: - pass - - ctypedef enum ocp_nlp_constraints_t: - pass - - ctypedef enum ocp_nlp_reg_t: - pass - - ctypedef struct ocp_nlp_plan: - pass - - ctypedef struct ocp_nlp_solver: - pass - - int ocp_nlp_cost_model_set(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in_, - int start_stage, const char *field, void *value) - int ocp_nlp_constraints_model_set(ocp_nlp_config *config, ocp_nlp_dims *dims, - ocp_nlp_in *in_, int stage, const char *field, void *value) - - # out - void ocp_nlp_out_set(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out, - int stage, const char *field, void *value) - void ocp_nlp_out_get(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out, - int stage, const char *field, void *value) - void ocp_nlp_get_at_stage(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_solver *solver, - int stage, const char *field, void *value) - int ocp_nlp_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out, - int stage, const char *field) - void ocp_nlp_constraint_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out, - int stage, const char *field, int *dims_out) - void ocp_nlp_cost_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out, - int stage, const char *field, int *dims_out) - void ocp_nlp_qp_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out, - int stage, const char *field, int *dims_out) - - # opts - void ocp_nlp_solver_opts_set(ocp_nlp_config *config, void *opts_, const char *field, void* value) - - # solver - void ocp_nlp_eval_residuals(ocp_nlp_solver *solver, ocp_nlp_in *nlp_in, ocp_nlp_out *nlp_out) - void ocp_nlp_eval_param_sens(ocp_nlp_solver *solver, char *field, int stage, int index, ocp_nlp_out *sens_nlp_out) - void ocp_nlp_eval_cost(ocp_nlp_solver *solver, ocp_nlp_in *nlp_in_, ocp_nlp_out *nlp_out) - - # get/set - void ocp_nlp_get(ocp_nlp_config *config, ocp_nlp_solver *solver, const char *field, void *return_value_) - void ocp_nlp_set(ocp_nlp_config *config, ocp_nlp_solver *solver, int stage, const char *field, void *value) diff --git a/third_party/acados/acados_template/builders.py b/third_party/acados/acados_template/builders.py deleted file mode 100644 index 8acc05b528..0000000000 --- a/third_party/acados/acados_template/builders.py +++ /dev/null @@ -1,130 +0,0 @@ -# -# Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -# Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -# Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -# Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# - -import os -import sys -from subprocess import DEVNULL, call, STDOUT - - -class CMakeBuilder: - """ - Class to work with the `CMake` build system. - """ - def __init__(self): - self._source_dir = None # private source directory, this is set to code_export_dir - self.build_dir = 'build' - self._build_dir = None # private build directory, usually rendered to abspath(build_dir) - self.generator = None - """Defines the generator, options can be found via `cmake --help` under 'Generator'. Type: string. Linux default 'Unix Makefiles', Windows 'Visual Studio 15 2017 Win64'; default value: `None`.""" - # set something for Windows - if os.name == 'nt': - self.generator = 'Visual Studio 15 2017 Win64' - self.build_targets = None - """A comma-separated list of the build targets, if `None` then all targets will be build; type: List of strings; default: `None`.""" - self.options_on = None - """List of strings as CMake options which are translated to '-D Opt[0]=ON -D Opt[1]=ON ...'; default: `None`.""" - - # Generate the command string for handling the cmake command. - def get_cmd1_cmake(self): - defines_str = '' - if self.options_on is not None: - defines_arr = [f' -D{opt}=ON' for opt in self.options_on] - defines_str = ' '.join(defines_arr) - generator_str = '' - if self.generator is not None: - generator_str = f' -G"{self.generator}"' - return f'cmake -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX="{self._source_dir}"{defines_str}{generator_str} -Wdev -S"{self._source_dir}" -B"{self._build_dir}"' - - # Generate the command string for handling the build. - def get_cmd2_build(self): - import multiprocessing - cmd = f'cmake --build "{self._build_dir}" --config Release -j{multiprocessing.cpu_count()}' - if self.build_targets is not None: - cmd += f' -t {self.build_targets}' - return cmd - - # Generate the command string for handling the install command. - def get_cmd3_install(self): - return f'cmake --install "{self._build_dir}"' - - def exec(self, code_export_directory, verbose=True): - """ - Execute the compilation using `CMake` with the given settings. - :param code_export_directory: must be the absolute path to the directory where the code was exported to - """ - if(os.path.isabs(code_export_directory) is False): - print(f'(W) the code export directory "{code_export_directory}" is not an absolute path!') - self._source_dir = code_export_directory - self._build_dir = os.path.abspath(self.build_dir) - try: - os.mkdir(self._build_dir) - except FileExistsError as e: - pass - - try: - os.chdir(self._build_dir) - cmd_str = self.get_cmd1_cmake() - print(f'call("{cmd_str})"') - retcode = call( - cmd_str, - shell=True, - stdout=None if verbose else DEVNULL, - stderr=None if verbose else STDOUT - ) - if retcode != 0: - raise RuntimeError(f'CMake command "{cmd_str}" was terminated by signal {retcode}') - cmd_str = self.get_cmd2_build() - print(f'call("{cmd_str}")') - retcode = call( - cmd_str, - shell=True, - stdout=None if verbose else DEVNULL, - stderr=None if verbose else STDOUT - ) - if retcode != 0: - raise RuntimeError(f'Build command "{cmd_str}" was terminated by signal {retcode}') - cmd_str = self.get_cmd3_install() - print(f'call("{cmd_str}")') - retcode = call( - cmd_str, - shell=True, - stdout=None if verbose else DEVNULL, - stderr=None if verbose else STDOUT - ) - if retcode != 0: - raise RuntimeError(f'Install command "{cmd_str}" was terminated by signal {retcode}') - except OSError as e: - print("Execution failed:", e, file=sys.stderr) - except Exception as e: - print("Execution failed:", e, file=sys.stderr) - exit(1) diff --git a/third_party/acados/acados_template/c_templates_tera/CMakeLists.in.txt b/third_party/acados/acados_template/c_templates_tera/CMakeLists.in.txt deleted file mode 100644 index 99bc26f750..0000000000 --- a/third_party/acados/acados_template/c_templates_tera/CMakeLists.in.txt +++ /dev/null @@ -1,397 +0,0 @@ -# -# Copyright (c) The acados authors. -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# - -{%- if solver_options.qp_solver %} - {%- set qp_solver = solver_options.qp_solver %} -{%- else %} - {%- set qp_solver = "FULL_CONDENSING_HPIPM" %} -{%- endif %} - -{%- if solver_options.hessian_approx %} - {%- set hessian_approx = solver_options.hessian_approx %} -{%- elif solver_options.sens_hess %} - {%- set hessian_approx = "EXACT" %} -{%- else %} - {%- set hessian_approx = "GAUSS_NEWTON" %} -{%- endif %} - -{%- if constraints.constr_type %} - {%- set constr_type = constraints.constr_type %} -{%- else %} - {%- set constr_type = "NONE" %} -{%- endif %} - -{%- if constraints.constr_type_e %} - {%- set constr_type_e = constraints.constr_type_e %} -{%- else %} - {%- set constr_type_e = "NONE" %} -{%- endif %} - -{%- if cost.cost_type %} - {%- set cost_type = cost.cost_type %} -{%- else %} - {%- set cost_type = "NONE" %} -{%- endif %} - -{%- if cost.cost_type_e %} - {%- set cost_type_e = cost.cost_type_e %} -{%- else %} - {%- set cost_type_e = "NONE" %} -{%- endif %} - -{%- if cost.cost_type_0 %} - {%- set cost_type_0 = cost.cost_type_0 %} -{%- else %} - {%- set cost_type_0 = "NONE" %} -{%- endif %} - -{%- if dims.nh %} - {%- set dims_nh = dims.nh %} -{%- else %} - {%- set dims_nh = 0 %} -{%- endif %} - -{%- if dims.nphi %} - {%- set dims_nphi = dims.nphi %} -{%- else %} - {%- set dims_nphi = 0 %} -{%- endif %} - -{%- if dims.nh_e %} - {%- set dims_nh_e = dims.nh_e %} -{%- else %} - {%- set dims_nh_e = 0 %} -{%- endif %} - -{%- if dims.nphi_e %} - {%- set dims_nphi_e = dims.nphi_e %} -{%- else %} - {%- set dims_nphi_e = 0 %} -{%- endif %} - -{%- if solver_options.model_external_shared_lib_dir %} - {%- set model_external_shared_lib_dir = solver_options.model_external_shared_lib_dir %} -{%- endif %} - -{%- if solver_options.model_external_shared_lib_name %} - {%- set model_external_shared_lib_name = solver_options.model_external_shared_lib_name %} -{%- endif %} - -{#- control operator #} -{%- if os and os == "pc" %} - {%- set control = "&" %} -{%- else %} - {%- set control = ";" %} -{%- endif %} - -{%- if acados_link_libs and os and os == "pc" %}{# acados linking libraries and flags #} - {%- set link_libs = acados_link_libs.qpoases ~ " " ~ acados_link_libs.hpmpc ~ " " ~ acados_link_libs.osqp -%} - {%- set openmp_flag = acados_link_libs.openmp %} -{%- else %} - {%- set openmp_flag = " " %} - {%- if qp_solver == "FULL_CONDENSING_QPOASES" %} - {%- set link_libs = "-lqpOASES_e" %} - {%- elif qp_solver == "FULL_CONDENSING_DAQP" %} - {%- set link_libs = "-ldaqp" %} - {%- else %} - {%- set link_libs = "" %} - {%- endif %} -{%- endif %} - -cmake_minimum_required(VERSION 3.13) - -project({{ model.name }}) - -# build options. -option(BUILD_ACADOS_SOLVER_LIB "Should the solver library acados_solver_{{ model.name }} be build?" OFF) -option(BUILD_ACADOS_OCP_SOLVER_LIB "Should the OCP solver library acados_ocp_solver_{{ model.name }} be build?" OFF) -option(BUILD_EXAMPLE "Should the example main_{{ model.name }} be build?" OFF) -{%- if solver_options.integrator_type != "DISCRETE" %} -option(BUILD_SIM_EXAMPLE "Should the simulation example main_sim_{{ model.name }} be build?" OFF) -option(BUILD_ACADOS_SIM_SOLVER_LIB "Should the simulation solver library acados_sim_solver_{{ model.name }} be build?" OFF) -{%- endif %} - - -if(CMAKE_CXX_COMPILER_ID MATCHES "GNU" AND CMAKE_SYSTEM_NAME MATCHES "Windows") - # MinGW, change to .lib such that mex recognizes it - set(CMAKE_SHARED_LIBRARY_SUFFIX ".lib") - set(CMAKE_SHARED_LIBRARY_PREFIX "") -endif() - - -# object target names -set(MODEL_OBJ model_{{ model.name }}) -set(OCP_OBJ ocp_{{ model.name }}) -set(SIM_OBJ sim_{{ model.name }}) - -# model -set(MODEL_SRC - {%- if model.dyn_ext_fun_type == "casadi" %} -{%- if solver_options.integrator_type == "ERK" %} - {{ model.name }}_model/{{ model.name }}_expl_ode_fun.c - {{ model.name }}_model/{{ model.name }}_expl_vde_forw.c - {{ model.name }}_model/{{ model.name }}_expl_vde_adj.c - {%- if hessian_approx == "EXACT" %} - {{ model.name }}_model/{{ model.name }}_expl_ode_hess.c - {%- endif %} -{%- elif solver_options.integrator_type == "IRK" %} - {{ model.name }}_model/{{ model.name }}_impl_dae_fun.c - {{ model.name }}_model/{{ model.name }}_impl_dae_fun_jac_x_xdot_z.c - {{ model.name }}_model/{{ model.name }}_impl_dae_jac_x_xdot_u_z.c - {%- if hessian_approx == "EXACT" %} - {{ model.name }}_model/{{ model.name }}_impl_dae_hess.c - {%- endif %} -{%- elif solver_options.integrator_type == "LIFTED_IRK" %} - {{ model.name }}_model/{{ model.name }}_impl_dae_fun.c - {{ model.name }}_model/{{ model.name }}_impl_dae_fun_jac_x_xdot_u.c - {%- if hessian_approx == "EXACT" %} - {{ model.name }}_model/{{ model.name }}_impl_dae_hess.c - {%- endif %} -{%- elif solver_options.integrator_type == "GNSF" %} - {% if model.gnsf.purely_linear != 1 %} - {{ model.name }}_model/{{ model.name }}_gnsf_phi_fun.c - {{ model.name }}_model/{{ model.name }}_gnsf_phi_fun_jac_y.c - {{ model.name }}_model/{{ model.name }}_gnsf_phi_jac_y_uhat.c - {% if model.gnsf.nontrivial_f_LO == 1 %} - {{ model.name }}_model/{{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz.c - {%- endif %} - {%- endif %} - {{ model.name }}_model/{{ model.name }}_gnsf_get_matrices_fun.c -{%- elif solver_options.integrator_type == "DISCRETE" %} - {{ model.name }}_model/{{ model.name }}_dyn_disc_phi_fun.c - {{ model.name }}_model/{{ model.name }}_dyn_disc_phi_fun_jac.c - {%- if hessian_approx == "EXACT" %} - {{ model.name }}_model/{{ model.name }}_dyn_disc_phi_fun_jac_hess.c - {%- endif %} -{%- endif -%} - {%- else %} - {{ model.name }}_model/{{ model.dyn_generic_source }} - {%- endif %} -) -add_library(${MODEL_OBJ} OBJECT ${MODEL_SRC} ) - -# optimal control problem - mostly CasADi exports -if(${BUILD_ACADOS_SOLVER_LIB} OR ${BUILD_ACADOS_OCP_SOLVER_LIB} OR ${BUILD_EXAMPLE}) - set(OCP_SRC -{%- if constr_type == "BGP" and dims_nphi > 0 %} - {{ model.name }}_constraints/{{ model.name }}_phi_constraint.c -{%- endif %} -{%- if constr_type_e == "BGP" and dims_nphi_e > 0 %} - {{ model.name }}_constraints/{{ model.name }}_phi_e_constraint.c -{%- endif %} - -{%- if constr_type == "BGH" and dims_nh > 0 %} - {{ model.name }}_constraints/{{ model.name }}_constr_h_fun_jac_uxt_zt.c - {{ model.name }}_constraints/{{ model.name }}_constr_h_fun.c - {%- if hessian_approx == "EXACT" %} - {{ model.name }}_constraints/{{ model.name }}_constr_h_fun_jac_uxt_zt_hess.c - {%- endif %} -{%- endif %} - -{%- if constr_type_e == "BGH" and dims_nh_e > 0 %} - {{ model.name }}_constraints/{{ model.name }}_constr_h_e_fun_jac_uxt_zt.c - {{ model.name }}_constraints/{{ model.name }}_constr_h_e_fun.c - {%- if hessian_approx == "EXACT" %} - {{ model.name }}_constraints/{{ model.name }}_constr_h_e_fun_jac_uxt_zt_hess.c - {%- endif %} -{%- endif %} - -{%- if cost_type_0 == "NONLINEAR_LS" %} - {{ model.name }}_cost/{{ model.name }}_cost_y_0_fun.c - {{ model.name }}_cost/{{ model.name }}_cost_y_0_fun_jac_ut_xt.c - {{ model.name }}_cost/{{ model.name }}_cost_y_0_hess.c -{%- elif cost_type_0 == "CONVEX_OVER_NONLINEAR" %} - {{ model.name }}_cost/{{ model.name }}_conl_cost_0_fun.c - {{ model.name }}_cost/{{ model.name }}_conl_cost_0_fun_jac_hess.c -{%- elif cost_type_0 == "EXTERNAL" %} - {%- if cost.cost_ext_fun_type_0 == "casadi" %} - {{ model.name }}_cost/{{ model.name }}_cost_ext_cost_0_fun.c - {{ model.name }}_cost/{{ model.name }}_cost_ext_cost_0_fun_jac.c - {{ model.name }}_cost/{{ model.name }}_cost_ext_cost_0_fun_jac_hess.c - {%- else %} - {{ model.name }}_cost/{{ cost.cost_source_ext_cost_0 }} - {%- endif %} -{%- endif %} -{%- if cost_type == "NONLINEAR_LS" %} - {{ model.name }}_cost/{{ model.name }}_cost_y_fun.c - {{ model.name }}_cost/{{ model.name }}_cost_y_fun_jac_ut_xt.c - {{ model.name }}_cost/{{ model.name }}_cost_y_hess.c -{%- elif cost_type == "CONVEX_OVER_NONLINEAR" %} - {{ model.name }}_cost/{{ model.name }}_conl_cost_fun.c - {{ model.name }}_cost/{{ model.name }}_conl_cost_fun_jac_hess.c -{%- elif cost_type == "EXTERNAL" %} - {%- if cost.cost_ext_fun_type == "casadi" %} - {{ model.name }}_cost/{{ model.name }}_cost_ext_cost_fun.c - {{ model.name }}_cost/{{ model.name }}_cost_ext_cost_fun_jac.c - {{ model.name }}_cost/{{ model.name }}_cost_ext_cost_fun_jac_hess.c - {%- elif cost.cost_source_ext_cost != cost.cost_source_ext_cost_0 %} - {{ model.name }}_cost/{{ cost.cost_source_ext_cost }} - {%- endif %} -{%- endif %} -{%- if cost_type_e == "NONLINEAR_LS" %} - {{ model.name }}_cost/{{ model.name }}_cost_y_e_fun.c - {{ model.name }}_cost/{{ model.name }}_cost_y_e_fun_jac_ut_xt.c - {{ model.name }}_cost/{{ model.name }}_cost_y_e_hess.c -{%- elif cost_type_e == "CONVEX_OVER_NONLINEAR" %} - {{ model.name }}_cost/{{ model.name }}_conl_cost_e_fun.c - {{ model.name }}_cost/{{ model.name }}_conl_cost_e_fun_jac_hess.c -{%- elif cost_type_e == "EXTERNAL" %} - {%- if cost.cost_ext_fun_type_e == "casadi" %} - {{ model.name }}_cost/{{ model.name }}_cost_ext_cost_e_fun.c - {{ model.name }}_cost/{{ model.name }}_cost_ext_cost_e_fun_jac.c - {{ model.name }}_cost/{{ model.name }}_cost_ext_cost_e_fun_jac_hess.c - {%- elif cost.cost_source_ext_cost_e != cost.cost_source_ext_cost_0 %} - {{ model.name }}_cost/{{ cost.cost_source_ext_cost_e }} - {%- endif %} -{%- endif %} - acados_solver_{{ model.name }}.c) - add_library(${OCP_OBJ} OBJECT ${OCP_SRC}) -endif() - -{%- if solver_options.integrator_type != "DISCRETE" %} -# for sim solver -if(${BUILD_ACADOS_SOLVER_LIB} OR ${BUILD_EXAMPLE} - {%- if solver_options.integrator_type != "DISCRETE" %} - OR ${BUILD_SIM_EXAMPLE} OR ${BUILD_ACADOS_SIM_SOLVER_LIB} - {%- endif -%} - ) - set(SIM_SRC acados_sim_solver_{{ model.name }}.c) - add_library(${SIM_OBJ} OBJECT ${SIM_SRC}) -endif() -{%- endif %} - -# for target example -set(EX_SRC main_{{ model.name }}.c) -set(EX_EXE main_{{ model.name }}) - -{%- if model_external_shared_lib_dir and model_external_shared_lib_name %} -set(EXTERNAL_DIR {{ model_external_shared_lib_dir | replace(from="\", to="/") }}) -set(EXTERNAL_LIB {{ model_external_shared_lib_name }}) -{%- else %} -set(EXTERNAL_DIR) -set(EXTERNAL_LIB) -{%- endif %} - -# set some search paths for preprocessor and linker -set(ACADOS_INCLUDE_PATH {{ acados_include_path | replace(from="\", to="/") }} CACHE PATH "Define the path which contains the include directory for acados.") -set(ACADOS_LIB_PATH {{ acados_lib_path | replace(from="\", to="/") }} CACHE PATH "Define the path which contains the lib directory for acados.") - -# c-compiler flags for debugging -set(CMAKE_C_FLAGS_DEBUG "-O0 -ggdb") - -set(CMAKE_C_FLAGS "-fPIC -std=c99 {{ openmp_flag }} -{%- if qp_solver == "FULL_CONDENSING_QPOASES" -%} - -DACADOS_WITH_QPOASES -{%- endif -%} -{%- if qp_solver == "FULL_CONDENSING_DAQP" -%} - -DACADOS_WITH_DAQP -{%- endif -%} -{%- if qp_solver == "PARTIAL_CONDENSING_OSQP" -%} - -DACADOS_WITH_OSQP -{%- endif -%} -{%- if qp_solver == "PARTIAL_CONDENSING_QPDUNES" -%} - -DACADOS_WITH_QPDUNES -{%- endif -%} -") -#-fno-diagnostics-show-line-numbers -g - -include_directories( - ${ACADOS_INCLUDE_PATH} - ${ACADOS_INCLUDE_PATH}/acados - ${ACADOS_INCLUDE_PATH}/blasfeo/include - ${ACADOS_INCLUDE_PATH}/hpipm/include -{%- if qp_solver == "FULL_CONDENSING_QPOASES" %} - ${ACADOS_INCLUDE_PATH}/qpOASES_e/ -{%- endif %} -{%- if qp_solver == "FULL_CONDENSING_DAQP" %} - ${ACADOS_INCLUDE_PATH}/daqp/include -{%- endif %} -) - -# linker flags -link_directories(${ACADOS_LIB_PATH}) - -# link to libraries -if(UNIX) - link_libraries(acados hpipm blasfeo m {{ link_libs }}) -else() - link_libraries(acados hpipm blasfeo {{ link_libs }}) -endif() - -# the targets - -# bundled_shared_lib -if(${BUILD_ACADOS_SOLVER_LIB}) - set(LIB_ACADOS_SOLVER acados_solver_{{ model.name }}) - add_library(${LIB_ACADOS_SOLVER} SHARED $ $ - {%- if solver_options.integrator_type != "DISCRETE" %} - $ - {%- endif -%} - ) - install(TARGETS ${LIB_ACADOS_SOLVER} DESTINATION ${CMAKE_INSTALL_PREFIX}) -endif(${BUILD_ACADOS_SOLVER_LIB}) - -# ocp_shared_lib -if(${BUILD_ACADOS_OCP_SOLVER_LIB}) - set(LIB_ACADOS_OCP_SOLVER acados_ocp_solver_{{ model.name }}) - add_library(${LIB_ACADOS_OCP_SOLVER} SHARED $ $) - # Specify libraries or flags to use when linking a given target and/or its dependents. - target_link_libraries(${LIB_ACADOS_OCP_SOLVER} PRIVATE ${EXTERNAL_LIB}) - target_link_directories(${LIB_ACADOS_OCP_SOLVER} PRIVATE ${EXTERNAL_DIR}) - install(TARGETS ${LIB_ACADOS_OCP_SOLVER} DESTINATION ${CMAKE_INSTALL_PREFIX}) -endif(${BUILD_ACADOS_OCP_SOLVER_LIB}) - -# example -if(${BUILD_EXAMPLE}) - add_executable(${EX_EXE} ${EX_SRC} $ $ - {%- if solver_options.integrator_type != "DISCRETE" %} - $ - {%- endif -%} - ) - install(TARGETS ${EX_EXE} DESTINATION ${CMAKE_INSTALL_PREFIX}) -endif(${BUILD_EXAMPLE}) - -{% if solver_options.integrator_type != "DISCRETE" -%} -# example_sim -if(${BUILD_SIM_EXAMPLE}) - set(EX_SIM_SRC main_sim_{{ model.name }}.c) - set(EX_SIM_EXE main_sim_{{ model.name }}) - add_executable(${EX_SIM_EXE} ${EX_SIM_SRC} $ $) - install(TARGETS ${EX_SIM_EXE} DESTINATION ${CMAKE_INSTALL_PREFIX}) -endif(${BUILD_SIM_EXAMPLE}) - -# sim_shared_lib -if(${BUILD_ACADOS_SIM_SOLVER_LIB}) - set(LIB_ACADOS_SIM_SOLVER acados_sim_solver_{{ model.name }}) - add_library(${LIB_ACADOS_SIM_SOLVER} SHARED $ $) - install(TARGETS ${LIB_ACADOS_SIM_SOLVER} DESTINATION ${CMAKE_INSTALL_PREFIX}) -endif(${BUILD_ACADOS_SIM_SOLVER_LIB}) -{%- endif %} - diff --git a/third_party/acados/acados_template/c_templates_tera/Makefile.in b/third_party/acados/acados_template/c_templates_tera/Makefile.in deleted file mode 100644 index fbefc08e38..0000000000 --- a/third_party/acados/acados_template/c_templates_tera/Makefile.in +++ /dev/null @@ -1,468 +0,0 @@ -# -# Copyright (c) The acados authors. -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# - -{%- if solver_options.qp_solver %} - {%- set qp_solver = solver_options.qp_solver %} -{%- else %} - {%- set qp_solver = "FULL_CONDENSING_HPIPM" %} -{%- endif %} - -{%- if solver_options.hessian_approx %} - {%- set hessian_approx = solver_options.hessian_approx %} -{%- elif solver_options.sens_hess %} - {%- set hessian_approx = "EXACT" %} -{%- else %} - {%- set hessian_approx = "GAUSS_NEWTON" %} -{%- endif %} - -{%- if constraints.constr_type %} - {%- set constr_type = constraints.constr_type %} -{%- else %} - {%- set constr_type = "NONE" %} -{%- endif %} - -{%- if constraints.constr_type_e %} - {%- set constr_type_e = constraints.constr_type_e %} -{%- else %} - {%- set constr_type_e = "NONE" %} -{%- endif %} - -{%- if cost.cost_type %} - {%- set cost_type = cost.cost_type %} -{%- else %} - {%- set cost_type = "NONE" %} -{%- endif %} - -{%- if cost.cost_type_e %} - {%- set cost_type_e = cost.cost_type_e %} -{%- else %} - {%- set cost_type_e = "NONE" %} -{%- endif %} - -{%- if cost.cost_type_0 %} - {%- set cost_type_0 = cost.cost_type_0 %} -{%- else %} - {%- set cost_type_0 = "NONE" %} -{%- endif %} - -{%- if dims.nh %} - {%- set dims_nh = dims.nh %} -{%- else %} - {%- set dims_nh = 0 %} -{%- endif %} - -{%- if dims.nphi %} - {%- set dims_nphi = dims.nphi %} -{%- else %} - {%- set dims_nphi = 0 %} -{%- endif %} - -{%- if dims.nh_e %} - {%- set dims_nh_e = dims.nh_e %} -{%- else %} - {%- set dims_nh_e = 0 %} -{%- endif %} - -{%- if dims.nphi_e %} - {%- set dims_nphi_e = dims.nphi_e %} -{%- else %} - {%- set dims_nphi_e = 0 %} -{%- endif %} -{%- if solver_options.model_external_shared_lib_dir %} - {%- set model_external_shared_lib_dir = solver_options.model_external_shared_lib_dir %} -{%- endif %} -{%- if solver_options.model_external_shared_lib_name %} - {%- set model_external_shared_lib_name = solver_options.model_external_shared_lib_name %} -{%- endif %} - -{# control operator #} -{%- if os and os == "pc" %} - {%- set control = "&" %} -{%- else %} - {%- set control = ";" %} -{%- endif %} - -{# acados linking libraries and flags #} -{%- if acados_link_libs and os and os == "pc" %} - {%- set link_libs = acados_link_libs.qpoases ~ " " ~ acados_link_libs.hpmpc ~ " " ~ acados_link_libs.osqp -%} - {%- set openmp_flag = acados_link_libs.openmp %} -{%- else %} - {%- set openmp_flag = " " %} - {%- if qp_solver == "FULL_CONDENSING_QPOASES" %} - {%- set link_libs = "-lqpOASES_e" %} - {%- elif qp_solver == "FULL_CONDENSING_DAQP" %} - {%- set link_libs = "-ldaqp" %} - {%- else %} - {%- set link_libs = "" %} - {%- endif %} -{%- endif %} - -# define sources and use make's implicit rules to generate object files (*.o) - -# model -MODEL_SRC= - {%- if model.dyn_ext_fun_type == "casadi" %} -{%- if solver_options.integrator_type == "ERK" %} -MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_expl_ode_fun.c -MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_expl_vde_forw.c -MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_expl_vde_adj.c - {%- if hessian_approx == "EXACT" %} -MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_expl_ode_hess.c - {%- endif %} -{%- elif solver_options.integrator_type == "IRK" %} -MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_impl_dae_fun.c -MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_impl_dae_fun_jac_x_xdot_z.c -MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_impl_dae_jac_x_xdot_u_z.c - {%- if hessian_approx == "EXACT" %} -MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_impl_dae_hess.c - {%- endif %} -{%- elif solver_options.integrator_type == "LIFTED_IRK" %} -MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_impl_dae_fun.c -MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_impl_dae_fun_jac_x_xdot_u.c - {%- if hessian_approx == "EXACT" %} -MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_impl_dae_hess.c - {%- endif %} -{%- elif solver_options.integrator_type == "GNSF" %} - {% if model.gnsf.purely_linear != 1 %} -MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_gnsf_phi_fun.c -MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_gnsf_phi_fun_jac_y.c -MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_gnsf_phi_jac_y_uhat.c - {% if model.gnsf.nontrivial_f_LO == 1 %} -MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz.c - {%- endif %} - {%- endif %} -MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_gnsf_get_matrices_fun.c -{%- elif solver_options.integrator_type == "DISCRETE" %} -MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_dyn_disc_phi_fun.c -MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_dyn_disc_phi_fun_jac.c - {%- if hessian_approx == "EXACT" %} -MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_dyn_disc_phi_fun_jac_hess.c - {%- endif %} -{%- endif %} - {%- else %} -MODEL_SRC+= {{ model.name }}_model/{{ model.dyn_generic_source }} - {%- endif %} -MODEL_OBJ := $(MODEL_SRC:.c=.o) - -# optimal control problem - mostly CasADi exports -OCP_SRC= -{%- if constr_type == "BGP" and dims_nphi > 0 %} -OCP_SRC+= {{ model.name }}_constraints/{{ model.name }}_phi_constraint.c -{%- endif %} -{%- if constr_type_e == "BGP" and dims_nphi_e > 0 %} -OCP_SRC+= {{ model.name }}_constraints/{{ model.name }}_phi_e_constraint.c -{%- endif %} - -{%- if constr_type == "BGH" and dims_nh > 0 %} -OCP_SRC+= {{ model.name }}_constraints/{{ model.name }}_constr_h_fun_jac_uxt_zt.c -OCP_SRC+= {{ model.name }}_constraints/{{ model.name }}_constr_h_fun.c - {%- if hessian_approx == "EXACT" %} -OCP_SRC+= {{ model.name }}_constraints/{{ model.name }}_constr_h_fun_jac_uxt_zt_hess.c - {%- endif %} -{%- endif %} - -{%- if constr_type_e == "BGH" and dims_nh_e > 0 %} -OCP_SRC+= {{ model.name }}_constraints/{{ model.name }}_constr_h_e_fun_jac_uxt_zt.c -OCP_SRC+= {{ model.name }}_constraints/{{ model.name }}_constr_h_e_fun.c - {%- if hessian_approx == "EXACT" %} -OCP_SRC+= {{ model.name }}_constraints/{{ model.name }}_constr_h_e_fun_jac_uxt_zt_hess.c - {%- endif %} -{%- endif %} - -{%- if cost_type_0 == "NONLINEAR_LS" %} -OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_y_0_fun.c -OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_y_0_fun_jac_ut_xt.c -OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_y_0_hess.c -{%- elif cost_type_0 == "CONVEX_OVER_NONLINEAR" %} -OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_conl_cost_0_fun.c -OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_conl_cost_0_fun_jac_hess.c -{%- elif cost_type_0 == "EXTERNAL" %} - {%- if cost.cost_ext_fun_type_0 == "casadi" %} -OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_ext_cost_0_fun.c -OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_ext_cost_0_fun_jac.c -OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_ext_cost_0_fun_jac_hess.c - {%- else %} -OCP_SRC+= {{ model.name }}_cost/{{ cost.cost_source_ext_cost_0 }} - {%- endif %} -{%- endif %} -{%- if cost_type == "NONLINEAR_LS" %} -OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_y_fun.c -OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_y_fun_jac_ut_xt.c -OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_y_hess.c -{%- elif cost_type == "CONVEX_OVER_NONLINEAR" %} -OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_conl_cost_fun.c -OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_conl_cost_fun_jac_hess.c -{%- elif cost_type == "EXTERNAL" %} - {%- if cost.cost_ext_fun_type == "casadi" %} -OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_ext_cost_fun.c -OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_ext_cost_fun_jac.c -OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_ext_cost_fun_jac_hess.c - {%- elif cost.cost_source_ext_cost != cost.cost_source_ext_cost_0 %} -OCP_SRC+= {{ model.name }}_cost/{{ cost.cost_source_ext_cost }} - {%- endif %} -{%- endif %} -{%- if cost_type_e == "NONLINEAR_LS" %} -OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_y_e_fun.c -OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_y_e_fun_jac_ut_xt.c -OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_y_e_hess.c -{%- elif cost_type_e == "CONVEX_OVER_NONLINEAR" %} -OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_conl_cost_e_fun.c -OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_conl_cost_e_fun_jac_hess.c -{%- elif cost_type_e == "EXTERNAL" %} - {%- if cost.cost_ext_fun_type_e == "casadi" %} -OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_ext_cost_e_fun.c -OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_ext_cost_e_fun_jac.c -OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_ext_cost_e_fun_jac_hess.c - {%- elif cost.cost_source_ext_cost_e != cost.cost_source_ext_cost_0 %} -OCP_SRC+= {{ model.name }}_cost/{{ cost.cost_source_ext_cost_e }} - {%- endif %} -{%- endif %} -{%- if solver_options.custom_update_filename %} - {%- if solver_options.custom_update_filename != "" %} -OCP_SRC+= {{ solver_options.custom_update_filename }} - {%- endif %} -{%- endif %} - -OCP_SRC+= acados_solver_{{ model.name }}.c -OCP_OBJ := $(OCP_SRC:.c=.o) - -# for sim solver -SIM_SRC= acados_sim_solver_{{ model.name }}.c -SIM_OBJ := $(SIM_SRC:.c=.o) - -# for target example -EX_SRC= main_{{ model.name }}.c -EX_OBJ := $(EX_SRC:.c=.o) -EX_EXE := $(EX_SRC:.c=) - -# for target example_sim -EX_SIM_SRC= main_sim_{{ model.name }}.c -EX_SIM_OBJ := $(EX_SIM_SRC:.c=.o) -EX_SIM_EXE := $(EX_SIM_SRC:.c=) - -# combine model, sim and ocp object files -OBJ= -OBJ+= $(MODEL_OBJ) -{%- if solver_options.integrator_type != "DISCRETE" %} -OBJ+= $(SIM_OBJ) -{%- endif %} -OBJ+= $(OCP_OBJ) - -EXTERNAL_DIR= -EXTERNAL_LIB= - -{%- if model_external_shared_lib_dir and model_external_shared_lib_name %} -EXTERNAL_DIR+= {{ model_external_shared_lib_dir }} -EXTERNAL_LIB+= {{ model_external_shared_lib_name }} -{%- endif %} - -INCLUDE_PATH = {{ acados_include_path }} -LIB_PATH = {{ acados_lib_path }} - -# preprocessor flags for make's implicit rules -{%- if qp_solver == "FULL_CONDENSING_QPOASES" %} -CPPFLAGS += -DACADOS_WITH_QPOASES -{%- endif %} -{%- if qp_solver == "FULL_CONDENSING_DAQP" %} -CPPFLAGS += -DACADOS_WITH_DAQP -{%- endif %} -{%- if qp_solver == "PARTIAL_CONDENSING_OSQP" %} -CPPFLAGS += -DACADOS_WITH_OSQP -{%- endif %} -{%- if qp_solver == "PARTIAL_CONDENSING_QPDUNES" %} -CPPFLAGS += -DACADOS_WITH_QPDUNES -{%- endif %} -CPPFLAGS+= -I$(INCLUDE_PATH) -CPPFLAGS+= -I$(INCLUDE_PATH)/acados -CPPFLAGS+= -I$(INCLUDE_PATH)/blasfeo/include -CPPFLAGS+= -I$(INCLUDE_PATH)/hpipm/include - {%- if qp_solver == "FULL_CONDENSING_QPOASES" %} -CPPFLAGS+= -I $(INCLUDE_PATH)/qpOASES_e/ - {%- endif %} - {%- if qp_solver == "FULL_CONDENSING_DAQP" %} -CPPFLAGS+= -I $(INCLUDE_PATH)/daqp/include - {%- endif %} - -{# c-compiler flags #} -# define the c-compiler flags for make's implicit rules -CFLAGS = -fPIC -std=c99 {{ openmp_flag }} {{ solver_options.ext_fun_compile_flags }}#-fno-diagnostics-show-line-numbers -g -# # Debugging -# CFLAGS += -g3 - -# linker flags -LDFLAGS+= -L$(LIB_PATH) - -# link to libraries -LDLIBS+= -lacados -LDLIBS+= -lhpipm -LDLIBS+= -lblasfeo -LDLIBS+= -lm -LDLIBS+= {{ link_libs }} - -# libraries -LIBACADOS_SOLVER=libacados_solver_{{ model.name }}{{ shared_lib_ext }} -LIBACADOS_OCP_SOLVER=libacados_ocp_solver_{{ model.name }}{{ shared_lib_ext }} -LIBACADOS_SIM_SOLVER=lib$(SIM_SRC:.c={{ shared_lib_ext }}) - -# virtual targets -.PHONY : all clean - -#all: clean example_sim example shared_lib -{% if solver_options.integrator_type == "DISCRETE" -%} -all: clean example -shared_lib: ocp_shared_lib -{%- else %} -all: clean example_sim example -shared_lib: bundled_shared_lib ocp_shared_lib sim_shared_lib -{%- endif %} - -# some linker targets -example: $(EX_OBJ) $(OBJ) - $(CC) $^ -o $(EX_EXE) $(LDFLAGS) $(LDLIBS) - -example_sim: $(EX_SIM_OBJ) $(MODEL_OBJ) $(SIM_OBJ) - $(CC) $^ -o $(EX_SIM_EXE) $(LDFLAGS) $(LDLIBS) - -{% if solver_options.integrator_type != "DISCRETE" -%} -bundled_shared_lib: $(OBJ) - $(CC) -shared $^ -o $(LIBACADOS_SOLVER) $(LDFLAGS) $(LDLIBS) -{%- endif %} - -ocp_shared_lib: $(OCP_OBJ) $(MODEL_OBJ) - $(CC) -shared $^ -o $(LIBACADOS_OCP_SOLVER) $(LDFLAGS) $(LDLIBS) \ - -L$(EXTERNAL_DIR) -l$(EXTERNAL_LIB) - -sim_shared_lib: $(SIM_OBJ) $(MODEL_OBJ) - $(CC) -shared $^ -o $(LIBACADOS_SIM_SOLVER) $(LDFLAGS) $(LDLIBS) - - -# Cython targets -ocp_cython_c: ocp_shared_lib - cython \ - -o acados_ocp_solver_pyx.c \ - -I $(INCLUDE_PATH)/../interfaces/acados_template/acados_template \ - $(INCLUDE_PATH)/../interfaces/acados_template/acados_template/acados_ocp_solver_pyx.pyx \ - -I {{ code_export_directory }} \ - -ocp_cython_o: ocp_cython_c - $(CC) $(ACADOS_FLAGS) -c -O2 \ - -fPIC \ - -o acados_ocp_solver_pyx.o \ - -I $(INCLUDE_PATH)/blasfeo/include/ \ - -I $(INCLUDE_PATH)/hpipm/include/ \ - -I $(INCLUDE_PATH) \ - {%- for path in cython_include_dirs %} - -I {{ path }} \ - {%- endfor %} - acados_ocp_solver_pyx.c \ - -ocp_cython: ocp_cython_o - $(CC) $(ACADOS_FLAGS) -shared \ - -o acados_ocp_solver_pyx{{ shared_lib_ext }} \ - -Wl,-rpath=$(LIB_PATH) \ - acados_ocp_solver_pyx.o \ - $(abspath .)/libacados_ocp_solver_{{ model.name }}{{ shared_lib_ext }} \ - $(LDFLAGS) $(LDLIBS) - -# Sim Cython targets -sim_cython_c: sim_shared_lib - cython \ - -o acados_sim_solver_pyx.c \ - -I $(INCLUDE_PATH)/../interfaces/acados_template/acados_template \ - $(INCLUDE_PATH)/../interfaces/acados_template/acados_template/acados_sim_solver_pyx.pyx \ - -I {{ code_export_directory }} \ - -sim_cython_o: sim_cython_c - $(CC) $(ACADOS_FLAGS) -c -O2 \ - -fPIC \ - -o acados_sim_solver_pyx.o \ - -I $(INCLUDE_PATH)/blasfeo/include/ \ - -I $(INCLUDE_PATH)/hpipm/include/ \ - -I $(INCLUDE_PATH) \ - {%- for path in cython_include_dirs %} - -I {{ path }} \ - {%- endfor %} - acados_sim_solver_pyx.c \ - -sim_cython: sim_cython_o - $(CC) $(ACADOS_FLAGS) -shared \ - -o acados_sim_solver_pyx{{ shared_lib_ext }} \ - -Wl,-rpath=$(LIB_PATH) \ - acados_sim_solver_pyx.o \ - $(abspath .)/libacados_sim_solver_{{ model.name }}{{ shared_lib_ext }} \ - $(LDFLAGS) $(LDLIBS) - -{%- if os and os == "pc" %} - -clean: - del \Q *.o 2>nul - del \Q *{{ shared_lib_ext }} 2>nul - del \Q main_{{ model.name }} 2>nul - -clean_ocp_shared_lib: - del \Q libacados_ocp_solver_{{ model.name }}{{ shared_lib_ext }} 2>nul - del \Q acados_solver_{{ model.name }}.o 2>nul - -clean_ocp_cython: - del \Q libacados_ocp_solver_{{ model.name }}{{ shared_lib_ext }} 2>nul - del \Q acados_solver_{{ model.name }}.o 2>nul - del \Q acados_ocp_solver_pyx{{ shared_lib_ext }} 2>nul - del \Q acados_ocp_solver_pyx.o 2>nul - -clean_sim_cython: - del \Q libacados_sim_solver_{{ model.name }}{{ shared_lib_ext }} 2>nul - del \Q acados_sim_solver_{{ model.name }}.o 2>nul - del \Q acados_sim_solver_pyx{{ shared_lib_ext }} 2>nul - del \Q acados_sim_solver_pyx.o 2>nul - -{%- else %} - -clean: - $(RM) $(OBJ) $(EX_OBJ) $(EX_SIM_OBJ) - $(RM) $(LIBACADOS_SOLVER) $(LIBACADOS_OCP_SOLVER) $(LIBACADOS_SIM_SOLVER) - $(RM) $(EX_EXE) $(EX_SIM_EXE) - -clean_ocp_shared_lib: - $(RM) $(LIBACADOS_OCP_SOLVER) - $(RM) $(OCP_OBJ) - -clean_ocp_cython: - $(RM) libacados_ocp_solver_{{ model.name }}{{ shared_lib_ext }} - $(RM) acados_solver_{{ model.name }}.o - $(RM) acados_ocp_solver_pyx{{ shared_lib_ext }} - $(RM) acados_ocp_solver_pyx.o - -clean_sim_cython: - $(RM) libacados_sim_solver_{{ model.name }}{{ shared_lib_ext }} - $(RM) acados_sim_solver_{{ model.name }}.o - $(RM) acados_sim_solver_pyx{{ shared_lib_ext }} - $(RM) acados_sim_solver_pyx.o - -{%- endif %} diff --git a/third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.c b/third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.c deleted file mode 100644 index 0cd098273c..0000000000 --- a/third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.c +++ /dev/null @@ -1,526 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - -{%- if solver_options.hessian_approx %} - {%- set hessian_approx = solver_options.hessian_approx %} -{%- elif solver_options.sens_hess %} - {%- set hessian_approx = "EXACT" %} -{%- else %} - {%- set hessian_approx = "GAUSS_NEWTON" %} -{%- endif %} -// standard -#include -#include - -// acados -#include "acados_c/external_function_interface.h" -#include "acados_c/sim_interface.h" -#include "acados_c/external_function_interface.h" - -#include "acados/sim/sim_common.h" -#include "acados/utils/external_function_generic.h" -#include "acados/utils/print.h" - - -// example specific -#include "{{ model.name }}_model/{{ model.name }}_model.h" -#include "acados_sim_solver_{{ model.name }}.h" - - -// ** solver data ** - -sim_solver_capsule * {{ model.name }}_acados_sim_solver_create_capsule() -{ - void* capsule_mem = malloc(sizeof(sim_solver_capsule)); - sim_solver_capsule *capsule = (sim_solver_capsule *) capsule_mem; - - return capsule; -} - - -int {{ model.name }}_acados_sim_solver_free_capsule(sim_solver_capsule * capsule) -{ - free(capsule); - return 0; -} - - -int {{ model.name }}_acados_sim_create(sim_solver_capsule * capsule) -{ - // initialize - const int nx = {{ model.name | upper }}_NX; - const int nu = {{ model.name | upper }}_NU; - const int nz = {{ model.name | upper }}_NZ; - const int np = {{ model.name | upper }}_NP; - bool tmp_bool; - - {#// double Tsim = {{ solver_options.tf / dims.N }};#} - double Tsim = {{ solver_options.Tsim }}; - - {% if solver_options.integrator_type == "IRK" %} - capsule->sim_impl_dae_fun = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})); - capsule->sim_impl_dae_fun_jac_x_xdot_z = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})); - capsule->sim_impl_dae_jac_x_xdot_u_z = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})); - - {%- if model.dyn_ext_fun_type == "casadi" %} - // external functions (implicit model) - capsule->sim_impl_dae_fun->casadi_fun = &{{ model.name }}_impl_dae_fun; - capsule->sim_impl_dae_fun->casadi_work = &{{ model.name }}_impl_dae_fun_work; - capsule->sim_impl_dae_fun->casadi_sparsity_in = &{{ model.name }}_impl_dae_fun_sparsity_in; - capsule->sim_impl_dae_fun->casadi_sparsity_out = &{{ model.name }}_impl_dae_fun_sparsity_out; - capsule->sim_impl_dae_fun->casadi_n_in = &{{ model.name }}_impl_dae_fun_n_in; - capsule->sim_impl_dae_fun->casadi_n_out = &{{ model.name }}_impl_dae_fun_n_out; - external_function_param_{{ model.dyn_ext_fun_type }}_create(capsule->sim_impl_dae_fun, np); - - capsule->sim_impl_dae_fun_jac_x_xdot_z->casadi_fun = &{{ model.name }}_impl_dae_fun_jac_x_xdot_z; - capsule->sim_impl_dae_fun_jac_x_xdot_z->casadi_work = &{{ model.name }}_impl_dae_fun_jac_x_xdot_z_work; - capsule->sim_impl_dae_fun_jac_x_xdot_z->casadi_sparsity_in = &{{ model.name }}_impl_dae_fun_jac_x_xdot_z_sparsity_in; - capsule->sim_impl_dae_fun_jac_x_xdot_z->casadi_sparsity_out = &{{ model.name }}_impl_dae_fun_jac_x_xdot_z_sparsity_out; - capsule->sim_impl_dae_fun_jac_x_xdot_z->casadi_n_in = &{{ model.name }}_impl_dae_fun_jac_x_xdot_z_n_in; - capsule->sim_impl_dae_fun_jac_x_xdot_z->casadi_n_out = &{{ model.name }}_impl_dae_fun_jac_x_xdot_z_n_out; - external_function_param_{{ model.dyn_ext_fun_type }}_create(capsule->sim_impl_dae_fun_jac_x_xdot_z, np); - - // external_function_param_{{ model.dyn_ext_fun_type }} impl_dae_jac_x_xdot_u_z; - capsule->sim_impl_dae_jac_x_xdot_u_z->casadi_fun = &{{ model.name }}_impl_dae_jac_x_xdot_u_z; - capsule->sim_impl_dae_jac_x_xdot_u_z->casadi_work = &{{ model.name }}_impl_dae_jac_x_xdot_u_z_work; - capsule->sim_impl_dae_jac_x_xdot_u_z->casadi_sparsity_in = &{{ model.name }}_impl_dae_jac_x_xdot_u_z_sparsity_in; - capsule->sim_impl_dae_jac_x_xdot_u_z->casadi_sparsity_out = &{{ model.name }}_impl_dae_jac_x_xdot_u_z_sparsity_out; - capsule->sim_impl_dae_jac_x_xdot_u_z->casadi_n_in = &{{ model.name }}_impl_dae_jac_x_xdot_u_z_n_in; - capsule->sim_impl_dae_jac_x_xdot_u_z->casadi_n_out = &{{ model.name }}_impl_dae_jac_x_xdot_u_z_n_out; - external_function_param_{{ model.dyn_ext_fun_type }}_create(capsule->sim_impl_dae_jac_x_xdot_u_z, np); - {%- else %} - capsule->sim_impl_dae_fun->fun = &{{ model.dyn_impl_dae_fun }}; - capsule->sim_impl_dae_fun_jac_x_xdot_z->fun = &{{ model.dyn_impl_dae_fun_jac }}; - capsule->sim_impl_dae_jac_x_xdot_u_z->fun = &{{ model.dyn_impl_dae_jac }}; - {%- endif %} - -{%- if hessian_approx == "EXACT" %} - capsule->sim_impl_dae_hess = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})); - // external_function_param_{{ model.dyn_ext_fun_type }} impl_dae_jac_x_xdot_u_z; - capsule->sim_impl_dae_hess->casadi_fun = &{{ model.name }}_impl_dae_hess; - capsule->sim_impl_dae_hess->casadi_work = &{{ model.name }}_impl_dae_hess_work; - capsule->sim_impl_dae_hess->casadi_sparsity_in = &{{ model.name }}_impl_dae_hess_sparsity_in; - capsule->sim_impl_dae_hess->casadi_sparsity_out = &{{ model.name }}_impl_dae_hess_sparsity_out; - capsule->sim_impl_dae_hess->casadi_n_in = &{{ model.name }}_impl_dae_hess_n_in; - capsule->sim_impl_dae_hess->casadi_n_out = &{{ model.name }}_impl_dae_hess_n_out; - external_function_param_{{ model.dyn_ext_fun_type }}_create(capsule->sim_impl_dae_hess, np); -{%- endif %} - - {% elif solver_options.integrator_type == "ERK" %} - // explicit ode - capsule->sim_forw_vde_casadi = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})); - capsule->sim_vde_adj_casadi = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})); - capsule->sim_expl_ode_fun_casadi = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})); - - capsule->sim_forw_vde_casadi->casadi_fun = &{{ model.name }}_expl_vde_forw; - capsule->sim_forw_vde_casadi->casadi_n_in = &{{ model.name }}_expl_vde_forw_n_in; - capsule->sim_forw_vde_casadi->casadi_n_out = &{{ model.name }}_expl_vde_forw_n_out; - capsule->sim_forw_vde_casadi->casadi_sparsity_in = &{{ model.name }}_expl_vde_forw_sparsity_in; - capsule->sim_forw_vde_casadi->casadi_sparsity_out = &{{ model.name }}_expl_vde_forw_sparsity_out; - capsule->sim_forw_vde_casadi->casadi_work = &{{ model.name }}_expl_vde_forw_work; - external_function_param_{{ model.dyn_ext_fun_type }}_create(capsule->sim_forw_vde_casadi, np); - - capsule->sim_vde_adj_casadi->casadi_fun = &{{ model.name }}_expl_vde_adj; - capsule->sim_vde_adj_casadi->casadi_n_in = &{{ model.name }}_expl_vde_adj_n_in; - capsule->sim_vde_adj_casadi->casadi_n_out = &{{ model.name }}_expl_vde_adj_n_out; - capsule->sim_vde_adj_casadi->casadi_sparsity_in = &{{ model.name }}_expl_vde_adj_sparsity_in; - capsule->sim_vde_adj_casadi->casadi_sparsity_out = &{{ model.name }}_expl_vde_adj_sparsity_out; - capsule->sim_vde_adj_casadi->casadi_work = &{{ model.name }}_expl_vde_adj_work; - external_function_param_{{ model.dyn_ext_fun_type }}_create(capsule->sim_vde_adj_casadi, np); - - capsule->sim_expl_ode_fun_casadi->casadi_fun = &{{ model.name }}_expl_ode_fun; - capsule->sim_expl_ode_fun_casadi->casadi_n_in = &{{ model.name }}_expl_ode_fun_n_in; - capsule->sim_expl_ode_fun_casadi->casadi_n_out = &{{ model.name }}_expl_ode_fun_n_out; - capsule->sim_expl_ode_fun_casadi->casadi_sparsity_in = &{{ model.name }}_expl_ode_fun_sparsity_in; - capsule->sim_expl_ode_fun_casadi->casadi_sparsity_out = &{{ model.name }}_expl_ode_fun_sparsity_out; - capsule->sim_expl_ode_fun_casadi->casadi_work = &{{ model.name }}_expl_ode_fun_work; - external_function_param_{{ model.dyn_ext_fun_type }}_create(capsule->sim_expl_ode_fun_casadi, np); - -{%- if hessian_approx == "EXACT" %} - capsule->sim_expl_ode_hess = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})); - // external_function_param_{{ model.dyn_ext_fun_type }} impl_dae_jac_x_xdot_u_z; - capsule->sim_expl_ode_hess->casadi_fun = &{{ model.name }}_expl_ode_hess; - capsule->sim_expl_ode_hess->casadi_work = &{{ model.name }}_expl_ode_hess_work; - capsule->sim_expl_ode_hess->casadi_sparsity_in = &{{ model.name }}_expl_ode_hess_sparsity_in; - capsule->sim_expl_ode_hess->casadi_sparsity_out = &{{ model.name }}_expl_ode_hess_sparsity_out; - capsule->sim_expl_ode_hess->casadi_n_in = &{{ model.name }}_expl_ode_hess_n_in; - capsule->sim_expl_ode_hess->casadi_n_out = &{{ model.name }}_expl_ode_hess_n_out; - external_function_param_{{ model.dyn_ext_fun_type }}_create(capsule->sim_expl_ode_hess, np); -{%- endif %} - - {% elif solver_options.integrator_type == "GNSF" -%} - {% if model.gnsf.purely_linear != 1 %} - capsule->sim_gnsf_phi_fun = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})); - capsule->sim_gnsf_phi_fun_jac_y = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})); - capsule->sim_gnsf_phi_jac_y_uhat = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})); - {% if model.gnsf.nontrivial_f_LO == 1 %} - capsule->sim_gnsf_f_lo_jac_x1_x1dot_u_z = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})); - {%- endif %} - {%- endif %} - capsule->sim_gnsf_get_matrices_fun = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})); - - {% if model.gnsf.purely_linear != 1 %} - capsule->sim_gnsf_phi_fun->casadi_fun = &{{ model.name }}_gnsf_phi_fun; - capsule->sim_gnsf_phi_fun->casadi_n_in = &{{ model.name }}_gnsf_phi_fun_n_in; - capsule->sim_gnsf_phi_fun->casadi_n_out = &{{ model.name }}_gnsf_phi_fun_n_out; - capsule->sim_gnsf_phi_fun->casadi_sparsity_in = &{{ model.name }}_gnsf_phi_fun_sparsity_in; - capsule->sim_gnsf_phi_fun->casadi_sparsity_out = &{{ model.name }}_gnsf_phi_fun_sparsity_out; - capsule->sim_gnsf_phi_fun->casadi_work = &{{ model.name }}_gnsf_phi_fun_work; - external_function_param_{{ model.dyn_ext_fun_type }}_create(capsule->sim_gnsf_phi_fun, np); - - capsule->sim_gnsf_phi_fun_jac_y->casadi_fun = &{{ model.name }}_gnsf_phi_fun_jac_y; - capsule->sim_gnsf_phi_fun_jac_y->casadi_n_in = &{{ model.name }}_gnsf_phi_fun_jac_y_n_in; - capsule->sim_gnsf_phi_fun_jac_y->casadi_n_out = &{{ model.name }}_gnsf_phi_fun_jac_y_n_out; - capsule->sim_gnsf_phi_fun_jac_y->casadi_sparsity_in = &{{ model.name }}_gnsf_phi_fun_jac_y_sparsity_in; - capsule->sim_gnsf_phi_fun_jac_y->casadi_sparsity_out = &{{ model.name }}_gnsf_phi_fun_jac_y_sparsity_out; - capsule->sim_gnsf_phi_fun_jac_y->casadi_work = &{{ model.name }}_gnsf_phi_fun_jac_y_work; - external_function_param_{{ model.dyn_ext_fun_type }}_create(capsule->sim_gnsf_phi_fun_jac_y, np); - - capsule->sim_gnsf_phi_jac_y_uhat->casadi_fun = &{{ model.name }}_gnsf_phi_jac_y_uhat; - capsule->sim_gnsf_phi_jac_y_uhat->casadi_n_in = &{{ model.name }}_gnsf_phi_jac_y_uhat_n_in; - capsule->sim_gnsf_phi_jac_y_uhat->casadi_n_out = &{{ model.name }}_gnsf_phi_jac_y_uhat_n_out; - capsule->sim_gnsf_phi_jac_y_uhat->casadi_sparsity_in = &{{ model.name }}_gnsf_phi_jac_y_uhat_sparsity_in; - capsule->sim_gnsf_phi_jac_y_uhat->casadi_sparsity_out = &{{ model.name }}_gnsf_phi_jac_y_uhat_sparsity_out; - capsule->sim_gnsf_phi_jac_y_uhat->casadi_work = &{{ model.name }}_gnsf_phi_jac_y_uhat_work; - external_function_param_{{ model.dyn_ext_fun_type }}_create(capsule->sim_gnsf_phi_jac_y_uhat, np); - - {% if model.gnsf.nontrivial_f_LO == 1 %} - capsule->sim_gnsf_f_lo_jac_x1_x1dot_u_z->casadi_fun = &{{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz; - capsule->sim_gnsf_f_lo_jac_x1_x1dot_u_z->casadi_n_in = &{{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz_n_in; - capsule->sim_gnsf_f_lo_jac_x1_x1dot_u_z->casadi_n_out = &{{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz_n_out; - capsule->sim_gnsf_f_lo_jac_x1_x1dot_u_z->casadi_sparsity_in = &{{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz_sparsity_in; - capsule->sim_gnsf_f_lo_jac_x1_x1dot_u_z->casadi_sparsity_out = &{{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz_sparsity_out; - capsule->sim_gnsf_f_lo_jac_x1_x1dot_u_z->casadi_work = &{{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz_work; - external_function_param_{{ model.dyn_ext_fun_type }}_create(capsule->sim_gnsf_f_lo_jac_x1_x1dot_u_z, np); - {%- endif %} - {%- endif %} - - capsule->sim_gnsf_get_matrices_fun->casadi_fun = &{{ model.name }}_gnsf_get_matrices_fun; - capsule->sim_gnsf_get_matrices_fun->casadi_n_in = &{{ model.name }}_gnsf_get_matrices_fun_n_in; - capsule->sim_gnsf_get_matrices_fun->casadi_n_out = &{{ model.name }}_gnsf_get_matrices_fun_n_out; - capsule->sim_gnsf_get_matrices_fun->casadi_sparsity_in = &{{ model.name }}_gnsf_get_matrices_fun_sparsity_in; - capsule->sim_gnsf_get_matrices_fun->casadi_sparsity_out = &{{ model.name }}_gnsf_get_matrices_fun_sparsity_out; - capsule->sim_gnsf_get_matrices_fun->casadi_work = &{{ model.name }}_gnsf_get_matrices_fun_work; - external_function_param_{{ model.dyn_ext_fun_type }}_create(capsule->sim_gnsf_get_matrices_fun, np); - {% endif %} - - // sim plan & config - sim_solver_plan_t plan; - plan.sim_solver = {{ solver_options.integrator_type }}; - - // create correct config based on plan - sim_config * {{ model.name }}_sim_config = sim_config_create(plan); - capsule->acados_sim_config = {{ model.name }}_sim_config; - - // sim dims - void *{{ model.name }}_sim_dims = sim_dims_create({{ model.name }}_sim_config); - capsule->acados_sim_dims = {{ model.name }}_sim_dims; - sim_dims_set({{ model.name }}_sim_config, {{ model.name }}_sim_dims, "nx", &nx); - sim_dims_set({{ model.name }}_sim_config, {{ model.name }}_sim_dims, "nu", &nu); - sim_dims_set({{ model.name }}_sim_config, {{ model.name }}_sim_dims, "nz", &nz); -{% if solver_options.integrator_type == "GNSF" %} - int gnsf_nx1 = {{ dims.gnsf_nx1 }}; - int gnsf_nz1 = {{ dims.gnsf_nz1 }}; - int gnsf_nout = {{ dims.gnsf_nout }}; - int gnsf_ny = {{ dims.gnsf_ny }}; - int gnsf_nuhat = {{ dims.gnsf_nuhat }}; - - sim_dims_set({{ model.name }}_sim_config, {{ model.name }}_sim_dims, "nx1", &gnsf_nx1); - sim_dims_set({{ model.name }}_sim_config, {{ model.name }}_sim_dims, "nz1", &gnsf_nz1); - sim_dims_set({{ model.name }}_sim_config, {{ model.name }}_sim_dims, "nout", &gnsf_nout); - sim_dims_set({{ model.name }}_sim_config, {{ model.name }}_sim_dims, "ny", &gnsf_ny); - sim_dims_set({{ model.name }}_sim_config, {{ model.name }}_sim_dims, "nuhat", &gnsf_nuhat); -{% endif %} - - // sim opts - sim_opts *{{ model.name }}_sim_opts = sim_opts_create({{ model.name }}_sim_config, {{ model.name }}_sim_dims); - capsule->acados_sim_opts = {{ model.name }}_sim_opts; - int tmp_int = {{ solver_options.sim_method_newton_iter }}; - sim_opts_set({{ model.name }}_sim_config, {{ model.name }}_sim_opts, "newton_iter", &tmp_int); - double tmp_double = {{ solver_options.sim_method_newton_tol }}; - sim_opts_set({{ model.name }}_sim_config, {{ model.name }}_sim_opts, "newton_tol", &tmp_double); - sim_collocation_type collocation_type = {{ solver_options.collocation_type }}; - sim_opts_set({{ model.name }}_sim_config, {{ model.name }}_sim_opts, "collocation_type", &collocation_type); - -{% if problem_class == "SIM" %} - tmp_int = {{ solver_options.sim_method_num_stages }}; - sim_opts_set({{ model.name }}_sim_config, {{ model.name }}_sim_opts, "num_stages", &tmp_int); - tmp_int = {{ solver_options.sim_method_num_steps }}; - sim_opts_set({{ model.name }}_sim_config, {{ model.name }}_sim_opts, "num_steps", &tmp_int); - - // options that are not available to AcadosOcpSolver - // (in OCP they will be determined by other options, like exact_hessian) - tmp_bool = {{ solver_options.sens_forw }}; - sim_opts_set({{ model.name }}_sim_config, {{ model.name }}_sim_opts, "sens_forw", &tmp_bool); - tmp_bool = {{ solver_options.sens_adj }}; - sim_opts_set({{ model.name }}_sim_config, {{ model.name }}_sim_opts, "sens_adj", &tmp_bool); - tmp_bool = {{ solver_options.sens_algebraic }}; - sim_opts_set({{ model.name }}_sim_config, {{ model.name }}_sim_opts, "sens_algebraic", &tmp_bool); - tmp_bool = {{ solver_options.sens_hess }}; - sim_opts_set({{ model.name }}_sim_config, {{ model.name }}_sim_opts, "sens_hess", &tmp_bool); - tmp_bool = {{ solver_options.output_z }}; - sim_opts_set({{ model.name }}_sim_config, {{ model.name }}_sim_opts, "output_z", &tmp_bool); - -{% else %} {# num_stages and num_steps of first shooting interval are used #} - tmp_int = {{ solver_options.sim_method_num_stages[0] }}; - sim_opts_set({{ model.name }}_sim_config, {{ model.name }}_sim_opts, "num_stages", &tmp_int); - tmp_int = {{ solver_options.sim_method_num_steps[0] }}; - sim_opts_set({{ model.name }}_sim_config, {{ model.name }}_sim_opts, "num_steps", &tmp_int); - tmp_bool = {{ solver_options.sim_method_jac_reuse[0] }}; - sim_opts_set({{ model.name }}_sim_config, {{ model.name }}_sim_opts, "jac_reuse", &tmp_bool); -{% endif %} - - // sim in / out - sim_in *{{ model.name }}_sim_in = sim_in_create({{ model.name }}_sim_config, {{ model.name }}_sim_dims); - capsule->acados_sim_in = {{ model.name }}_sim_in; - sim_out *{{ model.name }}_sim_out = sim_out_create({{ model.name }}_sim_config, {{ model.name }}_sim_dims); - capsule->acados_sim_out = {{ model.name }}_sim_out; - - sim_in_set({{ model.name }}_sim_config, {{ model.name }}_sim_dims, - {{ model.name }}_sim_in, "T", &Tsim); - - // model functions -{%- if solver_options.integrator_type == "IRK" %} - {{ model.name }}_sim_config->model_set({{ model.name }}_sim_in->model, - "impl_ode_fun", capsule->sim_impl_dae_fun); - {{ model.name }}_sim_config->model_set({{ model.name }}_sim_in->model, - "impl_ode_fun_jac_x_xdot", capsule->sim_impl_dae_fun_jac_x_xdot_z); - {{ model.name }}_sim_config->model_set({{ model.name }}_sim_in->model, - "impl_ode_jac_x_xdot_u", capsule->sim_impl_dae_jac_x_xdot_u_z); -{%- if hessian_approx == "EXACT" %} - {{ model.name }}_sim_config->model_set({{ model.name }}_sim_in->model, - "impl_dae_hess", capsule->sim_impl_dae_hess); -{%- endif %} - -{%- elif solver_options.integrator_type == "ERK" %} - {{ model.name }}_sim_config->model_set({{ model.name }}_sim_in->model, - "expl_vde_forw", capsule->sim_forw_vde_casadi); - {{ model.name }}_sim_config->model_set({{ model.name }}_sim_in->model, - "expl_vde_adj", capsule->sim_vde_adj_casadi); - {{ model.name }}_sim_config->model_set({{ model.name }}_sim_in->model, - "expl_ode_fun", capsule->sim_expl_ode_fun_casadi); -{%- if hessian_approx == "EXACT" %} - {{ model.name }}_sim_config->model_set({{ model.name }}_sim_in->model, - "expl_ode_hess", capsule->sim_expl_ode_hess); -{%- endif %} -{%- elif solver_options.integrator_type == "GNSF" %} - {% if model.gnsf.purely_linear != 1 %} - {{ model.name }}_sim_config->model_set({{ model.name }}_sim_in->model, - "phi_fun", capsule->sim_gnsf_phi_fun); - {{ model.name }}_sim_config->model_set({{ model.name }}_sim_in->model, - "phi_fun_jac_y", capsule->sim_gnsf_phi_fun_jac_y); - {{ model.name }}_sim_config->model_set({{ model.name }}_sim_in->model, - "phi_jac_y_uhat", capsule->sim_gnsf_phi_jac_y_uhat); - {% if model.gnsf.nontrivial_f_LO == 1 %} - {{ model.name }}_sim_config->model_set({{ model.name }}_sim_in->model, - "f_lo_jac_x1_x1dot_u_z", capsule->sim_gnsf_f_lo_jac_x1_x1dot_u_z); - {%- endif %} - {%- endif %} - {{ model.name }}_sim_config->model_set({{ model.name }}_sim_in->model, - "gnsf_get_matrices_fun", capsule->sim_gnsf_get_matrices_fun); -{%- endif %} - - // sim solver - sim_solver *{{ model.name }}_sim_solver = sim_solver_create({{ model.name }}_sim_config, - {{ model.name }}_sim_dims, {{ model.name }}_sim_opts); - capsule->acados_sim_solver = {{ model.name }}_sim_solver; - -{% if dims.np > 0 %} - /* initialize parameter values */ - double* p = calloc(np, sizeof(double)); - {% for item in parameter_values %} - {%- if item != 0 %} - p[{{ loop.index0 }}] = {{ item }}; - {%- endif %} - {%- endfor %} - - {{ model.name }}_acados_sim_update_params(capsule, p, np); - free(p); -{% endif %}{# if dims.np #} - - /* initialize input */ - // x - double x0[{{ dims.nx }}]; - for (int ii = 0; ii < {{ dims.nx }}; ii++) - x0[ii] = 0.0; - - sim_in_set({{ model.name }}_sim_config, {{ model.name }}_sim_dims, - {{ model.name }}_sim_in, "x", x0); - - - // u - double u0[{{ dims.nu }}]; - for (int ii = 0; ii < {{ dims.nu }}; ii++) - u0[ii] = 0.0; - - sim_in_set({{ model.name }}_sim_config, {{ model.name }}_sim_dims, - {{ model.name }}_sim_in, "u", u0); - - // S_forw - double S_forw[{{ dims.nx * (dims.nx + dims.nu) }}]; - for (int ii = 0; ii < {{ dims.nx * (dims.nx + dims.nu) }}; ii++) - S_forw[ii] = 0.0; - for (int ii = 0; ii < {{ dims.nx }}; ii++) - S_forw[ii + ii * {{ dims.nx }} ] = 1.0; - - - sim_in_set({{ model.name }}_sim_config, {{ model.name }}_sim_dims, - {{ model.name }}_sim_in, "S_forw", S_forw); - - int status = sim_precompute({{ model.name }}_sim_solver, {{ model.name }}_sim_in, {{ model.name }}_sim_out); - - return status; -} - - -int {{ model.name }}_acados_sim_solve(sim_solver_capsule *capsule) -{ - // integrate dynamics using acados sim_solver - int status = sim_solve(capsule->acados_sim_solver, - capsule->acados_sim_in, capsule->acados_sim_out); - if (status != 0) - printf("error in {{ model.name }}_acados_sim_solve()! Exiting.\n"); - - return status; -} - - -int {{ model.name }}_acados_sim_free(sim_solver_capsule *capsule) -{ - // free memory - sim_solver_destroy(capsule->acados_sim_solver); - sim_in_destroy(capsule->acados_sim_in); - sim_out_destroy(capsule->acados_sim_out); - sim_opts_destroy(capsule->acados_sim_opts); - sim_dims_destroy(capsule->acados_sim_dims); - sim_config_destroy(capsule->acados_sim_config); - - // free external function -{%- if solver_options.integrator_type == "IRK" %} - external_function_param_{{ model.dyn_ext_fun_type }}_free(capsule->sim_impl_dae_fun); - external_function_param_{{ model.dyn_ext_fun_type }}_free(capsule->sim_impl_dae_fun_jac_x_xdot_z); - external_function_param_{{ model.dyn_ext_fun_type }}_free(capsule->sim_impl_dae_jac_x_xdot_u_z); -{%- if hessian_approx == "EXACT" %} - external_function_param_{{ model.dyn_ext_fun_type }}_free(capsule->sim_impl_dae_hess); -{%- endif %} -{%- elif solver_options.integrator_type == "ERK" %} - external_function_param_{{ model.dyn_ext_fun_type }}_free(capsule->sim_forw_vde_casadi); - external_function_param_{{ model.dyn_ext_fun_type }}_free(capsule->sim_vde_adj_casadi); - external_function_param_{{ model.dyn_ext_fun_type }}_free(capsule->sim_expl_ode_fun_casadi); -{%- if hessian_approx == "EXACT" %} - external_function_param_{{ model.dyn_ext_fun_type }}_free(capsule->sim_expl_ode_hess); -{%- endif %} -{%- elif solver_options.integrator_type == "GNSF" %} - {% if model.gnsf.purely_linear != 1 %} - external_function_param_{{ model.dyn_ext_fun_type }}_free(capsule->sim_gnsf_phi_fun); - external_function_param_{{ model.dyn_ext_fun_type }}_free(capsule->sim_gnsf_phi_fun_jac_y); - external_function_param_{{ model.dyn_ext_fun_type }}_free(capsule->sim_gnsf_phi_jac_y_uhat); - {% if model.gnsf.nontrivial_f_LO == 1 %} - external_function_param_{{ model.dyn_ext_fun_type }}_free(capsule->sim_gnsf_f_lo_jac_x1_x1dot_u_z); - {%- endif %} - {%- endif %} - external_function_param_{{ model.dyn_ext_fun_type }}_free(capsule->sim_gnsf_get_matrices_fun); -{% endif %} - - return 0; -} - - -int {{ model.name }}_acados_sim_update_params(sim_solver_capsule *capsule, double *p, int np) -{ - int status = 0; - int casadi_np = {{ model.name | upper }}_NP; - - if (casadi_np != np) { - printf("{{ model.name }}_acados_sim_update_params: trying to set %i parameters for external functions." - " External function has %i parameters. Exiting.\n", np, casadi_np); - exit(1); - } - -{%- if solver_options.integrator_type == "ERK" %} - capsule->sim_forw_vde_casadi[0].set_param(capsule->sim_forw_vde_casadi, p); - capsule->sim_vde_adj_casadi[0].set_param(capsule->sim_vde_adj_casadi, p); - capsule->sim_expl_ode_fun_casadi[0].set_param(capsule->sim_expl_ode_fun_casadi, p); -{%- if hessian_approx == "EXACT" %} - capsule->sim_expl_ode_hess[0].set_param(capsule->sim_expl_ode_hess, p); -{%- endif %} -{%- elif solver_options.integrator_type == "IRK" %} - capsule->sim_impl_dae_fun[0].set_param(capsule->sim_impl_dae_fun, p); - capsule->sim_impl_dae_fun_jac_x_xdot_z[0].set_param(capsule->sim_impl_dae_fun_jac_x_xdot_z, p); - capsule->sim_impl_dae_jac_x_xdot_u_z[0].set_param(capsule->sim_impl_dae_jac_x_xdot_u_z, p); -{%- if hessian_approx == "EXACT" %} - capsule->sim_impl_dae_hess[0].set_param(capsule->sim_impl_dae_hess, p); -{%- endif %} -{%- elif solver_options.integrator_type == "GNSF" %} - {% if model.gnsf.purely_linear != 1 %} - capsule->sim_gnsf_phi_fun[0].set_param(capsule->sim_gnsf_phi_fun, p); - capsule->sim_gnsf_phi_fun_jac_y[0].set_param(capsule->sim_gnsf_phi_fun_jac_y, p); - capsule->sim_gnsf_phi_jac_y_uhat[0].set_param(capsule->sim_gnsf_phi_jac_y_uhat, p); - {% if model.gnsf.nontrivial_f_LO == 1 %} - capsule->sim_gnsf_f_lo_jac_x1_x1dot_u_z[0].set_param(capsule->sim_gnsf_f_lo_jac_x1_x1dot_u_z, p); - {%- endif %} - {%- endif %} - capsule->sim_gnsf_get_matrices_fun[0].set_param(capsule->sim_gnsf_get_matrices_fun, p); -{% endif %} - - return status; -} - -/* getters pointers to C objects*/ -sim_config * {{ model.name }}_acados_get_sim_config(sim_solver_capsule *capsule) -{ - return capsule->acados_sim_config; -}; - -sim_in * {{ model.name }}_acados_get_sim_in(sim_solver_capsule *capsule) -{ - return capsule->acados_sim_in; -}; - -sim_out * {{ model.name }}_acados_get_sim_out(sim_solver_capsule *capsule) -{ - return capsule->acados_sim_out; -}; - -void * {{ model.name }}_acados_get_sim_dims(sim_solver_capsule *capsule) -{ - return capsule->acados_sim_dims; -}; - -sim_opts * {{ model.name }}_acados_get_sim_opts(sim_solver_capsule *capsule) -{ - return capsule->acados_sim_opts; -}; - -sim_solver * {{ model.name }}_acados_get_sim_solver(sim_solver_capsule *capsule) -{ - return capsule->acados_sim_solver; -}; - diff --git a/third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.h b/third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.h deleted file mode 100644 index 59aee62f49..0000000000 --- a/third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.h +++ /dev/null @@ -1,101 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - -#ifndef ACADOS_SIM_{{ model.name }}_H_ -#define ACADOS_SIM_{{ model.name }}_H_ - -#include "acados_c/sim_interface.h" -#include "acados_c/external_function_interface.h" - -#define {{ model.name | upper }}_NX {{ dims.nx }} -#define {{ model.name | upper }}_NZ {{ dims.nz }} -#define {{ model.name | upper }}_NU {{ dims.nu }} -#define {{ model.name | upper }}_NP {{ dims.np }} - -#ifdef __cplusplus -extern "C" { -#endif - - -// ** capsule for solver data ** -typedef struct sim_solver_capsule -{ - // acados objects - sim_in *acados_sim_in; - sim_out *acados_sim_out; - sim_solver *acados_sim_solver; - sim_opts *acados_sim_opts; - sim_config *acados_sim_config; - void *acados_sim_dims; - - /* external functions */ - // ERK - external_function_param_{{ model.dyn_ext_fun_type }} * sim_forw_vde_casadi; - external_function_param_{{ model.dyn_ext_fun_type }} * sim_vde_adj_casadi; - external_function_param_{{ model.dyn_ext_fun_type }} * sim_expl_ode_fun_casadi; - external_function_param_{{ model.dyn_ext_fun_type }} * sim_expl_ode_hess; - - // IRK - external_function_param_{{ model.dyn_ext_fun_type }} * sim_impl_dae_fun; - external_function_param_{{ model.dyn_ext_fun_type }} * sim_impl_dae_fun_jac_x_xdot_z; - external_function_param_{{ model.dyn_ext_fun_type }} * sim_impl_dae_jac_x_xdot_u_z; - external_function_param_{{ model.dyn_ext_fun_type }} * sim_impl_dae_hess; - - // GNSF - external_function_param_{{ model.dyn_ext_fun_type }} * sim_gnsf_phi_fun; - external_function_param_{{ model.dyn_ext_fun_type }} * sim_gnsf_phi_fun_jac_y; - external_function_param_{{ model.dyn_ext_fun_type }} * sim_gnsf_phi_jac_y_uhat; - external_function_param_{{ model.dyn_ext_fun_type }} * sim_gnsf_f_lo_jac_x1_x1dot_u_z; - external_function_param_{{ model.dyn_ext_fun_type }} * sim_gnsf_get_matrices_fun; - -} sim_solver_capsule; - - -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_sim_create(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_sim_solve(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_sim_free(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_sim_update_params(sim_solver_capsule *capsule, double *value, int np); - -ACADOS_SYMBOL_EXPORT sim_config * {{ model.name }}_acados_get_sim_config(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT sim_in * {{ model.name }}_acados_get_sim_in(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT sim_out * {{ model.name }}_acados_get_sim_out(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT void * {{ model.name }}_acados_get_sim_dims(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT sim_opts * {{ model.name }}_acados_get_sim_opts(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT sim_solver * {{ model.name }}_acados_get_sim_solver(sim_solver_capsule *capsule); - - -ACADOS_SYMBOL_EXPORT sim_solver_capsule * {{ model.name }}_acados_sim_solver_create_capsule(void); -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_sim_solver_free_capsule(sim_solver_capsule *capsule); - -#ifdef __cplusplus -} -#endif - -#endif // ACADOS_SIM_{{ model.name }}_H_ diff --git a/third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.pxd b/third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.pxd deleted file mode 100644 index 153f98d13a..0000000000 --- a/third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.pxd +++ /dev/null @@ -1,51 +0,0 @@ -# -# Copyright (c) The acados authors. -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# - -cimport acados_sim_solver_common - -cdef extern from "acados_sim_solver_{{ model.name }}.h": - ctypedef struct sim_solver_capsule "sim_solver_capsule": - pass - - sim_solver_capsule * acados_sim_solver_create_capsule "{{ model.name }}_acados_sim_solver_create_capsule"() - int acados_sim_solver_free_capsule "{{ model.name }}_acados_sim_solver_free_capsule"(sim_solver_capsule *capsule) - - int acados_sim_create "{{ model.name }}_acados_sim_create"(sim_solver_capsule * capsule) - int acados_sim_solve "{{ model.name }}_acados_sim_solve"(sim_solver_capsule * capsule) - int acados_sim_free "{{ model.name }}_acados_sim_free"(sim_solver_capsule * capsule) - int acados_sim_update_params "{{ model.name }}_acados_sim_update_params"(sim_solver_capsule * capsule, double *value, int np_) - # int acados_sim_update_params_sparse "{{ model.name }}_acados_sim_update_params_sparse"(sim_solver_capsule * capsule, int stage, int *idx, double *p, int n_update) - - acados_sim_solver_common.sim_in *acados_get_sim_in "{{ model.name }}_acados_get_sim_in"(sim_solver_capsule * capsule) - acados_sim_solver_common.sim_out *acados_get_sim_out "{{ model.name }}_acados_get_sim_out"(sim_solver_capsule * capsule) - acados_sim_solver_common.sim_solver *acados_get_sim_solver "{{ model.name }}_acados_get_sim_solver"(sim_solver_capsule * capsule) - acados_sim_solver_common.sim_config *acados_get_sim_config "{{ model.name }}_acados_get_sim_config"(sim_solver_capsule * capsule) - acados_sim_solver_common.sim_opts *acados_get_sim_opts "{{ model.name }}_acados_get_sim_opts"(sim_solver_capsule * capsule) - void *acados_get_sim_dims "{{ model.name }}_acados_get_sim_dims"(sim_solver_capsule * capsule) diff --git a/third_party/acados/acados_template/c_templates_tera/acados_solver.in.c b/third_party/acados/acados_template/c_templates_tera/acados_solver.in.c deleted file mode 100644 index 5e36a53d10..0000000000 --- a/third_party/acados/acados_template/c_templates_tera/acados_solver.in.c +++ /dev/null @@ -1,2741 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - -// standard -#include -#include -#include -// acados -// #include "acados/utils/print.h" -#include "acados_c/ocp_nlp_interface.h" -#include "acados_c/external_function_interface.h" - -// example specific -#include "{{ model.name }}_model/{{ model.name }}_model.h" -#include "{{ model.name }}_constraints/{{ model.name }}_constraints.h" - -{%- if cost.cost_type != "LINEAR_LS" or cost.cost_type_e != "LINEAR_LS" or cost.cost_type_0 != "LINEAR_LS" %} -#include "{{ model.name }}_cost/{{ model.name }}_cost.h" -{%- endif %} - -{%- if not solver_options.custom_update_filename %} - {%- set custom_update_filename = "" %} -{% else %} - {%- set custom_update_filename = solver_options.custom_update_filename %} -{%- endif %} -{%- if not solver_options.custom_update_header_filename %} - {%- set custom_update_header_filename = "" %} -{% else %} - {%- set custom_update_header_filename = solver_options.custom_update_header_filename %} -{%- endif %} -{%- if custom_update_header_filename != "" %} -#include "{{ custom_update_header_filename }}" -{%- endif %} - - -#include "acados_solver_{{ model.name }}.h" - -#define NX {{ model.name | upper }}_NX -#define NZ {{ model.name | upper }}_NZ -#define NU {{ model.name | upper }}_NU -#define NP {{ model.name | upper }}_NP -#define NBX {{ model.name | upper }}_NBX -#define NBX0 {{ model.name | upper }}_NBX0 -#define NBU {{ model.name | upper }}_NBU -#define NSBX {{ model.name | upper }}_NSBX -#define NSBU {{ model.name | upper }}_NSBU -#define NSH {{ model.name | upper }}_NSH -#define NSG {{ model.name | upper }}_NSG -#define NSPHI {{ model.name | upper }}_NSPHI -#define NSHN {{ model.name | upper }}_NSHN -#define NSGN {{ model.name | upper }}_NSGN -#define NSPHIN {{ model.name | upper }}_NSPHIN -#define NSBXN {{ model.name | upper }}_NSBXN -#define NS {{ model.name | upper }}_NS -#define NSN {{ model.name | upper }}_NSN -#define NG {{ model.name | upper }}_NG -#define NBXN {{ model.name | upper }}_NBXN -#define NGN {{ model.name | upper }}_NGN -#define NY0 {{ model.name | upper }}_NY0 -#define NY {{ model.name | upper }}_NY -#define NYN {{ model.name | upper }}_NYN -// #define N {{ model.name | upper }}_N -#define NH {{ model.name | upper }}_NH -#define NPHI {{ model.name | upper }}_NPHI -#define NHN {{ model.name | upper }}_NHN -#define NPHIN {{ model.name | upper }}_NPHIN -#define NR {{ model.name | upper }}_NR - - -// ** solver data ** - -{{ model.name }}_solver_capsule * {{ model.name }}_acados_create_capsule(void) -{ - void* capsule_mem = malloc(sizeof({{ model.name }}_solver_capsule)); - {{ model.name }}_solver_capsule *capsule = ({{ model.name }}_solver_capsule *) capsule_mem; - - return capsule; -} - - -int {{ model.name }}_acados_free_capsule({{ model.name }}_solver_capsule *capsule) -{ - free(capsule); - return 0; -} - - -int {{ model.name }}_acados_create({{ model.name }}_solver_capsule* capsule) -{ - int N_shooting_intervals = {{ model.name | upper }}_N; - double* new_time_steps = NULL; // NULL -> don't alter the code generated time-steps - return {{ model.name }}_acados_create_with_discretization(capsule, N_shooting_intervals, new_time_steps); -} - - -int {{ model.name }}_acados_update_time_steps({{ model.name }}_solver_capsule* capsule, int N, double* new_time_steps) -{ - if (N != capsule->nlp_solver_plan->N) { - fprintf(stderr, "{{ model.name }}_acados_update_time_steps: given number of time steps (= %d) " \ - "differs from the currently allocated number of " \ - "time steps (= %d)!\n" \ - "Please recreate with new discretization and provide a new vector of time_stamps!\n", - N, capsule->nlp_solver_plan->N); - return 1; - } - - ocp_nlp_config * nlp_config = capsule->nlp_config; - ocp_nlp_dims * nlp_dims = capsule->nlp_dims; - ocp_nlp_in * nlp_in = capsule->nlp_in; - - for (int i = 0; i < N; i++) - { - ocp_nlp_in_set(nlp_config, nlp_dims, nlp_in, i, "Ts", &new_time_steps[i]); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "scaling", &new_time_steps[i]); - } - return 0; -} - -/** - * Internal function for {{ model.name }}_acados_create: step 1 - */ -void {{ model.name }}_acados_create_1_set_plan(ocp_nlp_plan_t* nlp_solver_plan, const int N) -{ - assert(N == nlp_solver_plan->N); - - /************************************************ - * plan - ************************************************/ - - {%- if solver_options.nlp_solver_type == "SQP" %} - nlp_solver_plan->nlp_solver = SQP; - {%- else %} - nlp_solver_plan->nlp_solver = SQP_RTI; - {%- endif %} - - nlp_solver_plan->ocp_qp_solver_plan.qp_solver = {{ solver_options.qp_solver }}; - - nlp_solver_plan->nlp_cost[0] = {{ cost.cost_type_0 }}; - for (int i = 1; i < N; i++) - nlp_solver_plan->nlp_cost[i] = {{ cost.cost_type }}; - - nlp_solver_plan->nlp_cost[N] = {{ cost.cost_type_e }}; - - for (int i = 0; i < N; i++) - { - {%- if solver_options.integrator_type == "DISCRETE" %} - nlp_solver_plan->nlp_dynamics[i] = DISCRETE_MODEL; - // discrete dynamics does not need sim solver option, this field is ignored - nlp_solver_plan->sim_solver_plan[i].sim_solver = INVALID_SIM_SOLVER; - {%- else %} - nlp_solver_plan->nlp_dynamics[i] = CONTINUOUS_MODEL; - nlp_solver_plan->sim_solver_plan[i].sim_solver = {{ solver_options.integrator_type }}; - {%- endif %} - } - - for (int i = 0; i < N; i++) - { - {%- if constraints.constr_type == "BGP" %} - nlp_solver_plan->nlp_constraints[i] = BGP; - {%- else -%} - nlp_solver_plan->nlp_constraints[i] = BGH; - {%- endif %} - } - - {%- if constraints.constr_type_e == "BGP" %} - nlp_solver_plan->nlp_constraints[N] = BGP; - {%- else %} - nlp_solver_plan->nlp_constraints[N] = BGH; - {%- endif %} - - {%- if solver_options.regularize_method == "NO_REGULARIZE" %} - nlp_solver_plan->regularization = NO_REGULARIZE; - {%- elif solver_options.regularize_method == "MIRROR" %} - nlp_solver_plan->regularization = MIRROR; - {%- elif solver_options.regularize_method == "PROJECT" %} - nlp_solver_plan->regularization = PROJECT; - {%- elif solver_options.regularize_method == "PROJECT_REDUC_HESS" %} - nlp_solver_plan->regularization = PROJECT_REDUC_HESS; - {%- elif solver_options.regularize_method == "CONVEXIFY" %} - nlp_solver_plan->regularization = CONVEXIFY; - {%- endif %} -} - - -/** - * Internal function for {{ model.name }}_acados_create: step 2 - */ -ocp_nlp_dims* {{ model.name }}_acados_create_2_create_and_set_dimensions({{ model.name }}_solver_capsule* capsule) -{ - ocp_nlp_plan_t* nlp_solver_plan = capsule->nlp_solver_plan; - const int N = nlp_solver_plan->N; - ocp_nlp_config* nlp_config = capsule->nlp_config; - - /************************************************ - * dimensions - ************************************************/ - #define NINTNP1MEMS 17 - int* intNp1mem = (int*)malloc( (N+1)*sizeof(int)*NINTNP1MEMS ); - - int* nx = intNp1mem + (N+1)*0; - int* nu = intNp1mem + (N+1)*1; - int* nbx = intNp1mem + (N+1)*2; - int* nbu = intNp1mem + (N+1)*3; - int* nsbx = intNp1mem + (N+1)*4; - int* nsbu = intNp1mem + (N+1)*5; - int* nsg = intNp1mem + (N+1)*6; - int* nsh = intNp1mem + (N+1)*7; - int* nsphi = intNp1mem + (N+1)*8; - int* ns = intNp1mem + (N+1)*9; - int* ng = intNp1mem + (N+1)*10; - int* nh = intNp1mem + (N+1)*11; - int* nphi = intNp1mem + (N+1)*12; - int* nz = intNp1mem + (N+1)*13; - int* ny = intNp1mem + (N+1)*14; - int* nr = intNp1mem + (N+1)*15; - int* nbxe = intNp1mem + (N+1)*16; - - for (int i = 0; i < N+1; i++) - { - // common - nx[i] = NX; - nu[i] = NU; - nz[i] = NZ; - ns[i] = NS; - // cost - ny[i] = NY; - // constraints - nbx[i] = NBX; - nbu[i] = NBU; - nsbx[i] = NSBX; - nsbu[i] = NSBU; - nsg[i] = NSG; - nsh[i] = NSH; - nsphi[i] = NSPHI; - ng[i] = NG; - nh[i] = NH; - nphi[i] = NPHI; - nr[i] = NR; - nbxe[i] = 0; - } - - // for initial state - nbx[0] = NBX0; - nsbx[0] = 0; - ns[0] = NS - NSBX; - nbxe[0] = {{ dims.nbxe_0 }}; - ny[0] = NY0; - - // terminal - common - nu[N] = 0; - nz[N] = 0; - ns[N] = NSN; - // cost - ny[N] = NYN; - // constraint - nbx[N] = NBXN; - nbu[N] = 0; - ng[N] = NGN; - nh[N] = NHN; - nphi[N] = NPHIN; - nr[N] = {{ dims.nr_e }}; - - nsbx[N] = NSBXN; - nsbu[N] = 0; - nsg[N] = NSGN; - nsh[N] = NSHN; - nsphi[N] = NSPHIN; - - /* create and set ocp_nlp_dims */ - ocp_nlp_dims * nlp_dims = ocp_nlp_dims_create(nlp_config); - - ocp_nlp_dims_set_opt_vars(nlp_config, nlp_dims, "nx", nx); - ocp_nlp_dims_set_opt_vars(nlp_config, nlp_dims, "nu", nu); - ocp_nlp_dims_set_opt_vars(nlp_config, nlp_dims, "nz", nz); - ocp_nlp_dims_set_opt_vars(nlp_config, nlp_dims, "ns", ns); - - for (int i = 0; i <= N; i++) - { - ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nbx", &nbx[i]); - ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nbu", &nbu[i]); - ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nsbx", &nsbx[i]); - ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nsbu", &nsbu[i]); - ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "ng", &ng[i]); - ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nsg", &nsg[i]); - ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nbxe", &nbxe[i]); - } - -{%- if cost.cost_type_0 == "NONLINEAR_LS" or cost.cost_type_0 == "LINEAR_LS" or cost.cost_type_0 == "CONVEX_OVER_NONLINEAR"%} - ocp_nlp_dims_set_cost(nlp_config, nlp_dims, 0, "ny", &ny[0]); -{%- endif %} - -{%- if cost.cost_type == "NONLINEAR_LS" or cost.cost_type == "LINEAR_LS" or cost.cost_type == "CONVEX_OVER_NONLINEAR"%} - for (int i = 1; i < N; i++) - ocp_nlp_dims_set_cost(nlp_config, nlp_dims, i, "ny", &ny[i]); -{%- endif %} - - for (int i = 0; i < N; i++) - { - {%- if constraints.constr_type == "BGH" and dims.nh > 0 %} - ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nh", &nh[i]); - ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nsh", &nsh[i]); - {%- elif constraints.constr_type == "BGP" and dims.nphi > 0 %} - ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nr", &nr[i]); - ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nphi", &nphi[i]); - ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nsphi", &nsphi[i]); - {%- endif %} - } - -{%- if constraints.constr_type_e == "BGH" %} - ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, N, "nh", &nh[N]); - ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, N, "nsh", &nsh[N]); -{%- elif constraints.constr_type_e == "BGP" %} - ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, N, "nr", &nr[N]); - ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, N, "nphi", &nphi[N]); - ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, N, "nsphi", &nsphi[N]); -{%- endif %} -{%- if cost.cost_type_e == "NONLINEAR_LS" or cost.cost_type_e == "LINEAR_LS" or cost.cost_type_e == "CONVEX_OVER_NONLINEAR"%} - ocp_nlp_dims_set_cost(nlp_config, nlp_dims, N, "ny", &ny[N]); -{%- endif %} - free(intNp1mem); - -{%- if solver_options.integrator_type == "GNSF" -%} - // GNSF specific dimensions - int gnsf_nx1 = {{ dims.gnsf_nx1 }}; - int gnsf_nz1 = {{ dims.gnsf_nz1 }}; - int gnsf_nout = {{ dims.gnsf_nout }}; - int gnsf_ny = {{ dims.gnsf_ny }}; - int gnsf_nuhat = {{ dims.gnsf_nuhat }}; - - for (int i = 0; i < N; i++) - { - if (nlp_solver_plan->sim_solver_plan[i].sim_solver == GNSF) - { - ocp_nlp_dims_set_dynamics(nlp_config, nlp_dims, i, "gnsf_nx1", &gnsf_nx1); - ocp_nlp_dims_set_dynamics(nlp_config, nlp_dims, i, "gnsf_nz1", &gnsf_nz1); - ocp_nlp_dims_set_dynamics(nlp_config, nlp_dims, i, "gnsf_nout", &gnsf_nout); - ocp_nlp_dims_set_dynamics(nlp_config, nlp_dims, i, "gnsf_ny", &gnsf_ny); - ocp_nlp_dims_set_dynamics(nlp_config, nlp_dims, i, "gnsf_nuhat", &gnsf_nuhat); - } - } -{%- endif %} -return nlp_dims; -} - - -/** - * Internal function for {{ model.name }}_acados_create: step 3 - */ -void {{ model.name }}_acados_create_3_create_and_set_functions({{ model.name }}_solver_capsule* capsule) -{ - const int N = capsule->nlp_solver_plan->N; - - /************************************************ - * external functions - ************************************************/ - -#define MAP_CASADI_FNC(__CAPSULE_FNC__, __MODEL_BASE_FNC__) do{ \ - capsule->__CAPSULE_FNC__.casadi_fun = & __MODEL_BASE_FNC__ ;\ - capsule->__CAPSULE_FNC__.casadi_n_in = & __MODEL_BASE_FNC__ ## _n_in; \ - capsule->__CAPSULE_FNC__.casadi_n_out = & __MODEL_BASE_FNC__ ## _n_out; \ - capsule->__CAPSULE_FNC__.casadi_sparsity_in = & __MODEL_BASE_FNC__ ## _sparsity_in; \ - capsule->__CAPSULE_FNC__.casadi_sparsity_out = & __MODEL_BASE_FNC__ ## _sparsity_out; \ - capsule->__CAPSULE_FNC__.casadi_work = & __MODEL_BASE_FNC__ ## _work; \ - external_function_param_casadi_create(&capsule->__CAPSULE_FNC__ , {{ dims.np }}); \ - }while(false) - -{% if constraints.constr_type == "BGP" %} - // constraints.constr_type == "BGP" - capsule->phi_constraint = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); - for (int i = 0; i < N; i++) - { - // nonlinear part of convex-composite constraint - MAP_CASADI_FNC(phi_constraint[i], {{ model.name }}_phi_constraint); - } -{%- endif %} - -{%- if constraints.constr_type_e == "BGP" %} - // constraints.constr_type_e == "BGP" - // nonlinear part of convex-composite constraint - MAP_CASADI_FNC(phi_e_constraint, {{ model.name }}_phi_e_constraint); -{%- endif %} - -{%- if constraints.constr_type == "BGH" and dims.nh > 0 %} - // constraints.constr_type == "BGH" and dims.nh > 0 - capsule->nl_constr_h_fun_jac = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); - for (int i = 0; i < N; i++) { - MAP_CASADI_FNC(nl_constr_h_fun_jac[i], {{ model.name }}_constr_h_fun_jac_uxt_zt); - } - capsule->nl_constr_h_fun = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); - for (int i = 0; i < N; i++) { - MAP_CASADI_FNC(nl_constr_h_fun[i], {{ model.name }}_constr_h_fun); - } - {% if solver_options.hessian_approx == "EXACT" %} - capsule->nl_constr_h_fun_jac_hess = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); - for (int i = 0; i < N; i++) { - MAP_CASADI_FNC(nl_constr_h_fun_jac_hess[i], {{ model.name }}_constr_h_fun_jac_uxt_zt_hess); - } - {% endif %} -{% endif %} - -{%- if constraints.constr_type_e == "BGH" and dims.nh_e > 0 %} - MAP_CASADI_FNC(nl_constr_h_e_fun_jac, {{ model.name }}_constr_h_e_fun_jac_uxt_zt); - MAP_CASADI_FNC(nl_constr_h_e_fun, {{ model.name }}_constr_h_e_fun); - - {%- if solver_options.hessian_approx == "EXACT" %} - MAP_CASADI_FNC(nl_constr_h_e_fun_jac_hess, {{ model.name }}_constr_h_e_fun_jac_uxt_zt_hess); - {% endif %} -{%- endif %} - -{% if solver_options.integrator_type == "ERK" %} - // explicit ode - capsule->forw_vde_casadi = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); - for (int i = 0; i < N; i++) { - MAP_CASADI_FNC(forw_vde_casadi[i], {{ model.name }}_expl_vde_forw); - } - - capsule->expl_ode_fun = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); - for (int i = 0; i < N; i++) { - MAP_CASADI_FNC(expl_ode_fun[i], {{ model.name }}_expl_ode_fun); - } - - {%- if solver_options.hessian_approx == "EXACT" %} - capsule->hess_vde_casadi = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); - for (int i = 0; i < N; i++) { - MAP_CASADI_FNC(hess_vde_casadi[i], {{ model.name }}_expl_ode_hess); - } - {%- endif %} - -{% elif solver_options.integrator_type == "IRK" %} - // implicit dae - capsule->impl_dae_fun = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})*N); - for (int i = 0; i < N; i++) { - {%- if model.dyn_ext_fun_type == "casadi" %} - MAP_CASADI_FNC(impl_dae_fun[i], {{ model.name }}_impl_dae_fun); - {%- else %} - capsule->impl_dae_fun[i].fun = &{{ model.dyn_impl_dae_fun }}; - external_function_param_{{ model.dyn_ext_fun_type }}_create(&capsule->impl_dae_fun[i], {{ dims.np }}); - {%- endif %} - } - - capsule->impl_dae_fun_jac_x_xdot_z = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})*N); - for (int i = 0; i < N; i++) { - {%- if model.dyn_ext_fun_type == "casadi" %} - MAP_CASADI_FNC(impl_dae_fun_jac_x_xdot_z[i], {{ model.name }}_impl_dae_fun_jac_x_xdot_z); - {%- else %} - capsule->impl_dae_fun_jac_x_xdot_z[i].fun = &{{ model.dyn_impl_dae_fun_jac }}; - external_function_param_{{ model.dyn_ext_fun_type }}_create(&capsule->impl_dae_fun_jac_x_xdot_z[i], {{ dims.np }}); - {%- endif %} - } - - capsule->impl_dae_jac_x_xdot_u_z = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})*N); - for (int i = 0; i < N; i++) { - {%- if model.dyn_ext_fun_type == "casadi" %} - MAP_CASADI_FNC(impl_dae_jac_x_xdot_u_z[i], {{ model.name }}_impl_dae_jac_x_xdot_u_z); - {%- else %} - capsule->impl_dae_jac_x_xdot_u_z[i].fun = &{{ model.dyn_impl_dae_jac }}; - external_function_param_{{ model.dyn_ext_fun_type }}_create(&capsule->impl_dae_jac_x_xdot_u_z[i], {{ dims.np }}); - {%- endif %} - } - - {%- if solver_options.hessian_approx == "EXACT" %} - capsule->impl_dae_hess = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})*N); - for (int i = 0; i < N; i++) { - MAP_CASADI_FNC(impl_dae_hess[i], {{ model.name }}_impl_dae_hess); - } - {%- endif %} -{% elif solver_options.integrator_type == "LIFTED_IRK" %} - // external functions (implicit model) - capsule->impl_dae_fun = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})*N); - for (int i = 0; i < N; i++) { - MAP_CASADI_FNC(impl_dae_fun[i], {{ model.name }}_impl_dae_fun); - } - - capsule->impl_dae_fun_jac_x_xdot_u = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})*N); - for (int i = 0; i < N; i++) { - MAP_CASADI_FNC(impl_dae_fun_jac_x_xdot_u[i], {{ model.name }}_impl_dae_fun_jac_x_xdot_u); - } - -{% elif solver_options.integrator_type == "GNSF" %} - {% if model.gnsf.purely_linear != 1 %} - capsule->gnsf_phi_fun = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); - for (int i = 0; i < N; i++) { - MAP_CASADI_FNC(gnsf_phi_fun[i], {{ model.name }}_gnsf_phi_fun); - } - - capsule->gnsf_phi_fun_jac_y = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); - for (int i = 0; i < N; i++) { - MAP_CASADI_FNC(gnsf_phi_fun_jac_y[i], {{ model.name }}_gnsf_phi_fun_jac_y); - } - - capsule->gnsf_phi_jac_y_uhat = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); - for (int i = 0; i < N; i++) { - MAP_CASADI_FNC(gnsf_phi_jac_y_uhat[i], {{ model.name }}_gnsf_phi_jac_y_uhat); - } - - {% if model.gnsf.nontrivial_f_LO == 1 %} - capsule->gnsf_f_lo_jac_x1_x1dot_u_z = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); - for (int i = 0; i < N; i++) { - MAP_CASADI_FNC(gnsf_f_lo_jac_x1_x1dot_u_z[i], {{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz); - } - {%- endif %} - {%- endif %} - capsule->gnsf_get_matrices_fun = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); - for (int i = 0; i < N; i++) { - MAP_CASADI_FNC(gnsf_get_matrices_fun[i], {{ model.name }}_gnsf_get_matrices_fun); - } -{% elif solver_options.integrator_type == "DISCRETE" %} - // discrete dynamics - capsule->discr_dyn_phi_fun = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})*N); - for (int i = 0; i < N; i++) - { - {%- if model.dyn_ext_fun_type == "casadi" %} - MAP_CASADI_FNC(discr_dyn_phi_fun[i], {{ model.name }}_dyn_disc_phi_fun); - {%- else %} - capsule->discr_dyn_phi_fun[i].fun = &{{ model.dyn_disc_fun }}; - external_function_param_{{ model.dyn_ext_fun_type }}_create(&capsule->discr_dyn_phi_fun[i], {{ dims.np }}); - {%- endif %} - } - - capsule->discr_dyn_phi_fun_jac_ut_xt = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})*N); - for (int i = 0; i < N; i++) - { - {%- if model.dyn_ext_fun_type == "casadi" %} - MAP_CASADI_FNC(discr_dyn_phi_fun_jac_ut_xt[i], {{ model.name }}_dyn_disc_phi_fun_jac); - {%- else %} - capsule->discr_dyn_phi_fun_jac_ut_xt[i].fun = &{{ model.dyn_disc_fun_jac }}; - external_function_param_{{ model.dyn_ext_fun_type }}_create(&capsule->discr_dyn_phi_fun_jac_ut_xt[i], {{ dims.np }}); - {%- endif %} - } - - {%- if solver_options.hessian_approx == "EXACT" %} - capsule->discr_dyn_phi_fun_jac_ut_xt_hess = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})*N); - for (int i = 0; i < N; i++) - { - {%- if model.dyn_ext_fun_type == "casadi" %} - MAP_CASADI_FNC(discr_dyn_phi_fun_jac_ut_xt_hess[i], {{ model.name }}_dyn_disc_phi_fun_jac_hess); - {%- else %} - capsule->discr_dyn_phi_fun_jac_ut_xt_hess[i].fun = &{{ model.dyn_disc_fun_jac_hess }}; - external_function_param_{{ model.dyn_ext_fun_type }}_create(&capsule->discr_dyn_phi_fun_jac_ut_xt_hess[i], {{ dims.np }}); - {%- endif %} - } - {%- endif %} -{%- endif %} - - -{%- if cost.cost_type_0 == "NONLINEAR_LS" %} - // nonlinear least squares function - MAP_CASADI_FNC(cost_y_0_fun, {{ model.name }}_cost_y_0_fun); - MAP_CASADI_FNC(cost_y_0_fun_jac_ut_xt, {{ model.name }}_cost_y_0_fun_jac_ut_xt); - MAP_CASADI_FNC(cost_y_0_hess, {{ model.name }}_cost_y_0_hess); - -{%- elif cost.cost_type_0 == "CONVEX_OVER_NONLINEAR" %} - // convex-over-nonlinear cost - MAP_CASADI_FNC(conl_cost_0_fun, {{ model.name }}_conl_cost_0_fun); - MAP_CASADI_FNC(conl_cost_0_fun_jac_hess, {{ model.name }}_conl_cost_0_fun_jac_hess); - -{%- elif cost.cost_type_0 == "EXTERNAL" %} - // external cost - {%- if cost.cost_ext_fun_type_0 == "casadi" %} - MAP_CASADI_FNC(ext_cost_0_fun, {{ model.name }}_cost_ext_cost_0_fun); - {%- else %} - capsule->ext_cost_0_fun.fun = &{{ cost.cost_function_ext_cost_0 }}; - external_function_param_{{ cost.cost_ext_fun_type_0 }}_create(&capsule->ext_cost_0_fun, {{ dims.np }}); - {%- endif %} - - // external cost - {%- if cost.cost_ext_fun_type_0 == "casadi" %} - MAP_CASADI_FNC(ext_cost_0_fun_jac, {{ model.name }}_cost_ext_cost_0_fun_jac); - {%- else %} - capsule->ext_cost_0_fun_jac.fun = &{{ cost.cost_function_ext_cost_0 }}; - external_function_param_{{ cost.cost_ext_fun_type_0 }}_create(&capsule->ext_cost_0_fun_jac, {{ dims.np }}); - {%- endif %} - - // external cost - {%- if cost.cost_ext_fun_type_0 == "casadi" %} - MAP_CASADI_FNC(ext_cost_0_fun_jac_hess, {{ model.name }}_cost_ext_cost_0_fun_jac_hess); - {%- else %} - capsule->ext_cost_0_fun_jac_hess.fun = &{{ cost.cost_function_ext_cost_0 }}; - external_function_param_{{ cost.cost_ext_fun_type_0 }}_create(&capsule->ext_cost_0_fun_jac_hess, {{ dims.np }}); - {%- endif %} -{%- endif %} - -{%- if cost.cost_type == "NONLINEAR_LS" %} - // nonlinear least squares cost - capsule->cost_y_fun = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); - for (int i = 0; i < N-1; i++) - { - MAP_CASADI_FNC(cost_y_fun[i], {{ model.name }}_cost_y_fun); - } - - capsule->cost_y_fun_jac_ut_xt = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); - for (int i = 0; i < N-1; i++) - { - MAP_CASADI_FNC(cost_y_fun_jac_ut_xt[i], {{ model.name }}_cost_y_fun_jac_ut_xt); - } - - capsule->cost_y_hess = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); - for (int i = 0; i < N-1; i++) - { - MAP_CASADI_FNC(cost_y_hess[i], {{ model.name }}_cost_y_hess); - } - -{%- elif cost.cost_type_0 == "CONVEX_OVER_NONLINEAR" %} - // convex-over-nonlinear cost - capsule->conl_cost_fun = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); - for (int i = 0; i < N-1; i++) - { - MAP_CASADI_FNC(conl_cost_fun[i], {{ model.name }}_conl_cost_fun); - } - capsule->conl_cost_fun_jac_hess = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); - for (int i = 0; i < N-1; i++) - { - MAP_CASADI_FNC(conl_cost_fun_jac_hess[i], {{ model.name }}_conl_cost_fun_jac_hess); - } - -{%- elif cost.cost_type == "EXTERNAL" %} - // external cost - capsule->ext_cost_fun = (external_function_param_{{ cost.cost_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ cost.cost_ext_fun_type }})*N); - for (int i = 0; i < N-1; i++) - { - {%- if cost.cost_ext_fun_type == "casadi" %} - MAP_CASADI_FNC(ext_cost_fun[i], {{ model.name }}_cost_ext_cost_fun); - {%- else %} - capsule->ext_cost_fun[i].fun = &{{ cost.cost_function_ext_cost }}; - external_function_param_{{ cost.cost_ext_fun_type }}_create(&capsule->ext_cost_fun[i], {{ dims.np }}); - {%- endif %} - } - - capsule->ext_cost_fun_jac = (external_function_param_{{ cost.cost_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ cost.cost_ext_fun_type }})*N); - for (int i = 0; i < N-1; i++) - { - {%- if cost.cost_ext_fun_type == "casadi" %} - MAP_CASADI_FNC(ext_cost_fun_jac[i], {{ model.name }}_cost_ext_cost_fun_jac); - {%- else %} - capsule->ext_cost_fun_jac[i].fun = &{{ cost.cost_function_ext_cost }}; - external_function_param_{{ cost.cost_ext_fun_type }}_create(&capsule->ext_cost_fun_jac[i], {{ dims.np }}); - {%- endif %} - } - - capsule->ext_cost_fun_jac_hess = (external_function_param_{{ cost.cost_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ cost.cost_ext_fun_type }})*N); - for (int i = 0; i < N-1; i++) - { - {%- if cost.cost_ext_fun_type == "casadi" %} - MAP_CASADI_FNC(ext_cost_fun_jac_hess[i], {{ model.name }}_cost_ext_cost_fun_jac_hess); - {%- else %} - capsule->ext_cost_fun_jac_hess[i].fun = &{{ cost.cost_function_ext_cost }}; - external_function_param_{{ cost.cost_ext_fun_type }}_create(&capsule->ext_cost_fun_jac_hess[i], {{ dims.np }}); - {%- endif %} - } -{%- endif %} - -{%- if cost.cost_type_e == "NONLINEAR_LS" %} - // nonlinear least square function - MAP_CASADI_FNC(cost_y_e_fun, {{ model.name }}_cost_y_e_fun); - MAP_CASADI_FNC(cost_y_e_fun_jac_ut_xt, {{ model.name }}_cost_y_e_fun_jac_ut_xt); - MAP_CASADI_FNC(cost_y_e_hess, {{ model.name }}_cost_y_e_hess); - -{%- elif cost.cost_type_e == "CONVEX_OVER_NONLINEAR" %} - // convex-over-nonlinear cost - MAP_CASADI_FNC(conl_cost_e_fun, {{ model.name }}_conl_cost_e_fun); - MAP_CASADI_FNC(conl_cost_e_fun_jac_hess, {{ model.name }}_conl_cost_e_fun_jac_hess); - -{%- elif cost.cost_type_e == "EXTERNAL" %} - // external cost - function - {%- if cost.cost_ext_fun_type_e == "casadi" %} - MAP_CASADI_FNC(ext_cost_e_fun, {{ model.name }}_cost_ext_cost_e_fun); - {% else %} - capsule->ext_cost_e_fun.fun = &{{ cost.cost_function_ext_cost_e }}; - external_function_param_{{ cost.cost_ext_fun_type_e }}_create(&capsule->ext_cost_e_fun, {{ dims.np }}); - {%- endif %} - - // external cost - jacobian - {%- if cost.cost_ext_fun_type_e == "casadi" %} - MAP_CASADI_FNC(ext_cost_e_fun_jac, {{ model.name }}_cost_ext_cost_e_fun_jac); - {%- else %} - capsule->ext_cost_e_fun_jac.fun = &{{ cost.cost_function_ext_cost_e }}; - external_function_param_{{ cost.cost_ext_fun_type_e }}_create(&capsule->ext_cost_e_fun_jac, {{ dims.np }}); - {%- endif %} - - // external cost - hessian - {%- if cost.cost_ext_fun_type_e == "casadi" %} - MAP_CASADI_FNC(ext_cost_e_fun_jac_hess, {{ model.name }}_cost_ext_cost_e_fun_jac_hess); - {%- else %} - capsule->ext_cost_e_fun_jac_hess.fun = &{{ cost.cost_function_ext_cost_e }}; - external_function_param_{{ cost.cost_ext_fun_type_e }}_create(&capsule->ext_cost_e_fun_jac_hess, {{ dims.np }}); - {%- endif %} -{%- endif %} - -#undef MAP_CASADI_FNC -} - - -/** - * Internal function for {{ model.name }}_acados_create: step 4 - */ -void {{ model.name }}_acados_create_4_set_default_parameters({{ model.name }}_solver_capsule* capsule) { -{%- if dims.np > 0 %} - const int N = capsule->nlp_solver_plan->N; - // initialize parameters to nominal value - double* p = calloc(NP, sizeof(double)); - {%- for item in parameter_values %} - {%- if item != 0 %} - p[{{ loop.index0 }}] = {{ item }}; - {%- endif %} - {%- endfor %} - - for (int i = 0; i <= N; i++) { - {{ model.name }}_acados_update_params(capsule, i, p, NP); - } - free(p); -{%- else %} - // no parameters defined -{%- endif %}{# if dims.np #} -} - - -/** - * Internal function for {{ model.name }}_acados_create: step 5 - */ -void {{ model.name }}_acados_create_5_set_nlp_in({{ model.name }}_solver_capsule* capsule, const int N, double* new_time_steps) -{ - assert(N == capsule->nlp_solver_plan->N); - ocp_nlp_config* nlp_config = capsule->nlp_config; - ocp_nlp_dims* nlp_dims = capsule->nlp_dims; - - /************************************************ - * nlp_in - ************************************************/ -// ocp_nlp_in * nlp_in = ocp_nlp_in_create(nlp_config, nlp_dims); -// capsule->nlp_in = nlp_in; - ocp_nlp_in * nlp_in = capsule->nlp_in; - - // set up time_steps - {% set all_equal = true -%} - {%- set val = solver_options.time_steps[0] %} - {%- for j in range(start=1, end=dims.N) %} - {%- if val != solver_options.time_steps[j] %} - {%- set_global all_equal = false %} - {%- break %} - {%- endif %} - {%- endfor %} - - if (new_time_steps) { - {{ model.name }}_acados_update_time_steps(capsule, N, new_time_steps); - } else { - {%- if all_equal == true -%} - // all time_steps are identical - double time_step = {{ solver_options.time_steps[0] }}; - for (int i = 0; i < N; i++) - { - ocp_nlp_in_set(nlp_config, nlp_dims, nlp_in, i, "Ts", &time_step); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "scaling", &time_step); - } - {%- else -%} - // time_steps are different - double* time_steps = malloc(N*sizeof(double)); - {%- for j in range(end=dims.N) %} - time_steps[{{ j }}] = {{ solver_options.time_steps[j] }}; - {%- endfor %} - {{ model.name }}_acados_update_time_steps(capsule, N, time_steps); - free(time_steps); - {%- endif %} - } - - /**** Dynamics ****/ - for (int i = 0; i < N; i++) - { - {%- if solver_options.integrator_type == "ERK" %} - ocp_nlp_dynamics_model_set(nlp_config, nlp_dims, nlp_in, i, "expl_vde_forw", &capsule->forw_vde_casadi[i]); - ocp_nlp_dynamics_model_set(nlp_config, nlp_dims, nlp_in, i, "expl_ode_fun", &capsule->expl_ode_fun[i]); - {%- if solver_options.hessian_approx == "EXACT" %} - ocp_nlp_dynamics_model_set(nlp_config, nlp_dims, nlp_in, i, "expl_ode_hess", &capsule->hess_vde_casadi[i]); - {%- endif %} - {% elif solver_options.integrator_type == "IRK" %} - ocp_nlp_dynamics_model_set(nlp_config, nlp_dims, nlp_in, i, "impl_dae_fun", &capsule->impl_dae_fun[i]); - ocp_nlp_dynamics_model_set(nlp_config, nlp_dims, nlp_in, i, - "impl_dae_fun_jac_x_xdot_z", &capsule->impl_dae_fun_jac_x_xdot_z[i]); - ocp_nlp_dynamics_model_set(nlp_config, nlp_dims, nlp_in, i, - "impl_dae_jac_x_xdot_u", &capsule->impl_dae_jac_x_xdot_u_z[i]); - {%- if solver_options.hessian_approx == "EXACT" %} - ocp_nlp_dynamics_model_set(nlp_config, nlp_dims, nlp_in, i, "impl_dae_hess", &capsule->impl_dae_hess[i]); - {%- endif %} - {% elif solver_options.integrator_type == "LIFTED_IRK" %} - ocp_nlp_dynamics_model_set(nlp_config, nlp_dims, nlp_in, i, "impl_dae_fun", &capsule->impl_dae_fun[i]); - ocp_nlp_dynamics_model_set(nlp_config, nlp_dims, nlp_in, i, - "impl_dae_fun_jac_x_xdot_u", &capsule->impl_dae_fun_jac_x_xdot_u[i]); - {% elif solver_options.integrator_type == "GNSF" %} - {% if model.gnsf.purely_linear != 1 %} - ocp_nlp_dynamics_model_set(nlp_config, nlp_dims, nlp_in, i, "phi_fun", &capsule->gnsf_phi_fun[i]); - ocp_nlp_dynamics_model_set(nlp_config, nlp_dims, nlp_in, i, "phi_fun_jac_y", &capsule->gnsf_phi_fun_jac_y[i]); - ocp_nlp_dynamics_model_set(nlp_config, nlp_dims, nlp_in, i, "phi_jac_y_uhat", &capsule->gnsf_phi_jac_y_uhat[i]); - {% if model.gnsf.nontrivial_f_LO == 1 %} - ocp_nlp_dynamics_model_set(nlp_config, nlp_dims, nlp_in, i, "f_lo_jac_x1_x1dot_u_z", - &capsule->gnsf_f_lo_jac_x1_x1dot_u_z[i]); - {%- endif %} - {%- endif %} - ocp_nlp_dynamics_model_set(nlp_config, nlp_dims, nlp_in, i, "gnsf_get_matrices_fun", - &capsule->gnsf_get_matrices_fun[i]); - {% elif solver_options.integrator_type == "DISCRETE" %} - ocp_nlp_dynamics_model_set(nlp_config, nlp_dims, nlp_in, i, "disc_dyn_fun", &capsule->discr_dyn_phi_fun[i]); - ocp_nlp_dynamics_model_set(nlp_config, nlp_dims, nlp_in, i, "disc_dyn_fun_jac", - &capsule->discr_dyn_phi_fun_jac_ut_xt[i]); - {%- if solver_options.hessian_approx == "EXACT" %} - ocp_nlp_dynamics_model_set(nlp_config, nlp_dims, nlp_in, i, "disc_dyn_fun_jac_hess", - &capsule->discr_dyn_phi_fun_jac_ut_xt_hess[i]); - {%- endif %} - {%- endif %} - } - - /**** Cost ****/ - -{%- if dims.ny_0 == 0 %} -{%- elif cost.cost_type_0 == "NONLINEAR_LS" or cost.cost_type_0 == "LINEAR_LS" or cost.cost_type_0 == "CONVEX_OVER_NONLINEAR" %} - double* yref_0 = calloc(NY0, sizeof(double)); - // change only the non-zero elements: - {%- for j in range(end=dims.ny_0) %} - {%- if cost.yref_0[j] != 0 %} - yref_0[{{ j }}] = {{ cost.yref_0[j] }}; - {%- endif %} - {%- endfor %} - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "yref", yref_0); - free(yref_0); -{%- endif %} - - -{%- if dims.ny == 0 %} -{%- elif cost.cost_type == "NONLINEAR_LS" or cost.cost_type == "LINEAR_LS" or cost.cost_type == "CONVEX_OVER_NONLINEAR" %} - double* yref = calloc(NY, sizeof(double)); - // change only the non-zero elements: - {%- for j in range(end=dims.ny) %} - {%- if cost.yref[j] != 0 %} - yref[{{ j }}] = {{ cost.yref[j] }}; - {%- endif %} - {%- endfor %} - - for (int i = 1; i < N; i++) - { - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "yref", yref); - } - free(yref); -{%- endif %} - - -{%- if dims.ny_e == 0 %} -{%- elif cost.cost_type_e == "NONLINEAR_LS" or cost.cost_type_e == "LINEAR_LS" or cost.cost_type_e == "CONVEX_OVER_NONLINEAR" %} - double* yref_e = calloc(NYN, sizeof(double)); - // change only the non-zero elements: - {%- for j in range(end=dims.ny_e) %} - {%- if cost.yref_e[j] != 0 %} - yref_e[{{ j }}] = {{ cost.yref_e[j] }}; - {%- endif %} - {%- endfor %} - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "yref", yref_e); - free(yref_e); -{%- endif %} - -{%- if dims.ny_0 == 0 %} -{%- elif cost.cost_type_0 == "NONLINEAR_LS" or cost.cost_type_0 == "LINEAR_LS" %} - double* W_0 = calloc(NY0*NY0, sizeof(double)); - // change only the non-zero elements: - {%- for j in range(end=dims.ny_0) %} - {%- for k in range(end=dims.ny_0) %} - {%- if cost.W_0[j][k] != 0 %} - W_0[{{ j }}+(NY0) * {{ k }}] = {{ cost.W_0[j][k] }}; - {%- endif %} - {%- endfor %} - {%- endfor %} - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "W", W_0); - free(W_0); -{%- endif %} - -{%- if dims.ny == 0 %} -{%- elif cost.cost_type == "NONLINEAR_LS" or cost.cost_type == "LINEAR_LS" %} - double* W = calloc(NY*NY, sizeof(double)); - // change only the non-zero elements: - {%- for j in range(end=dims.ny) %} - {%- for k in range(end=dims.ny) %} - {%- if cost.W[j][k] != 0 %} - W[{{ j }}+(NY) * {{ k }}] = {{ cost.W[j][k] }}; - {%- endif %} - {%- endfor %} - {%- endfor %} - - for (int i = 1; i < N; i++) - { - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "W", W); - } - free(W); -{%- endif %} - -{%- if dims.ny_e == 0 %} -{%- elif cost.cost_type_e == "NONLINEAR_LS" or cost.cost_type_e == "LINEAR_LS" %} - double* W_e = calloc(NYN*NYN, sizeof(double)); - // change only the non-zero elements: - {%- for j in range(end=dims.ny_e) %} - {%- for k in range(end=dims.ny_e) %} - {%- if cost.W_e[j][k] != 0 %} - W_e[{{ j }}+(NYN) * {{ k }}] = {{ cost.W_e[j][k] }}; - {%- endif %} - {%- endfor %} - {%- endfor %} - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "W", W_e); - free(W_e); -{%- endif %} - -{%- if dims.ny_0 == 0 %} -{%- elif cost.cost_type_0 == "LINEAR_LS" %} - double* Vx_0 = calloc(NY0*NX, sizeof(double)); - // change only the non-zero elements: - {%- for j in range(end=dims.ny_0) %} - {%- for k in range(end=dims.nx) %} - {%- if cost.Vx_0[j][k] != 0 %} - Vx_0[{{ j }}+(NY0) * {{ k }}] = {{ cost.Vx_0[j][k] }}; - {%- endif %} - {%- endfor %} - {%- endfor %} - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "Vx", Vx_0); - free(Vx_0); - - {%- if dims.nu > 0 %} - double* Vu_0 = calloc(NY0*NU, sizeof(double)); - // change only the non-zero elements: - {%- for j in range(end=dims.ny_0) %} - {%- for k in range(end=dims.nu) %} - {%- if cost.Vu_0[j][k] != 0 %} - Vu_0[{{ j }}+(NY0) * {{ k }}] = {{ cost.Vu_0[j][k] }}; - {%- endif %} - {%- endfor %} - {%- endfor %} - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "Vu", Vu_0); - free(Vu_0); - {%- endif %} - - {%- if dims.nz > 0 %} - double* Vz_0 = calloc(NY0*NZ, sizeof(double)); - // change only the non-zero elements: - {% for j in range(end=dims.ny_0) %} - {%- for k in range(end=dims.nz) %} - {%- if cost.Vz_0[j][k] != 0 %} - Vz_0[{{ j }}+(NY0) * {{ k }}] = {{ cost.Vz_0[j][k] }}; - {%- endif %} - {%- endfor %} - {%- endfor %} - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "Vz", Vz_0); - free(Vz_0); - {%- endif %} -{%- endif %} - -{%- if dims.ny == 0 %} -{%- elif cost.cost_type == "LINEAR_LS" %} - double* Vx = calloc(NY*NX, sizeof(double)); - // change only the non-zero elements: - {%- for j in range(end=dims.ny) %} - {%- for k in range(end=dims.nx) %} - {%- if cost.Vx[j][k] != 0 %} - Vx[{{ j }}+(NY) * {{ k }}] = {{ cost.Vx[j][k] }}; - {%- endif %} - {%- endfor %} - {%- endfor %} - for (int i = 1; i < N; i++) - { - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "Vx", Vx); - } - free(Vx); - - {% if dims.nu > 0 %} - double* Vu = calloc(NY*NU, sizeof(double)); - // change only the non-zero elements: - {% for j in range(end=dims.ny) %} - {%- for k in range(end=dims.nu) %} - {%- if cost.Vu[j][k] != 0 %} - Vu[{{ j }}+(NY) * {{ k }}] = {{ cost.Vu[j][k] }}; - {%- endif %} - {%- endfor %} - {%- endfor %} - - for (int i = 1; i < N; i++) - { - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "Vu", Vu); - } - free(Vu); - {%- endif %} - - {%- if dims.nz > 0 %} - double* Vz = calloc(NY*NZ, sizeof(double)); - // change only the non-zero elements: - {% for j in range(end=dims.ny) %} - {%- for k in range(end=dims.nz) %} - {%- if cost.Vz[j][k] != 0 %} - Vz[{{ j }}+(NY) * {{ k }}] = {{ cost.Vz[j][k] }}; - {%- endif %} - {%- endfor %} - {%- endfor %} - - for (int i = 1; i < N; i++) - { - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "Vz", Vz); - } - free(Vz); - {%- endif %} -{%- endif %}{# LINEAR LS #} - -{%- if dims.ny_e == 0 %} -{%- elif cost.cost_type_e == "LINEAR_LS" %} - double* Vx_e = calloc(NYN*NX, sizeof(double)); - // change only the non-zero elements: - {% for j in range(end=dims.ny_e) %} - {%- for k in range(end=dims.nx) %} - {%- if cost.Vx_e[j][k] != 0 %} - Vx_e[{{ j }}+(NYN) * {{ k }}] = {{ cost.Vx_e[j][k] }}; - {%- endif %} - {%- endfor %} - {%- endfor %} - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "Vx", Vx_e); - free(Vx_e); -{%- endif %} - -{%- if cost.cost_type_0 == "NONLINEAR_LS" %} - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "nls_y_fun", &capsule->cost_y_0_fun); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "nls_y_fun_jac", &capsule->cost_y_0_fun_jac_ut_xt); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "nls_y_hess", &capsule->cost_y_0_hess); -{%- elif cost.cost_type_0 == "CONVEX_OVER_NONLINEAR" %} - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "conl_cost_fun", &capsule->conl_cost_0_fun); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "conl_cost_fun_jac_hess", &capsule->conl_cost_0_fun_jac_hess); -{%- elif cost.cost_type_0 == "EXTERNAL" %} - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "ext_cost_fun", &capsule->ext_cost_0_fun); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "ext_cost_fun_jac", &capsule->ext_cost_0_fun_jac); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "ext_cost_fun_jac_hess", &capsule->ext_cost_0_fun_jac_hess); -{%- endif %} - -{%- if cost.cost_type == "NONLINEAR_LS" %} - for (int i = 1; i < N; i++) - { - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "nls_y_fun", &capsule->cost_y_fun[i-1]); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "nls_y_fun_jac", &capsule->cost_y_fun_jac_ut_xt[i-1]); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "nls_y_hess", &capsule->cost_y_hess[i-1]); - } -{%- elif cost.cost_type == "CONVEX_OVER_NONLINEAR" %} - for (int i = 1; i < N; i++) - { - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "conl_cost_fun", &capsule->conl_cost_fun[i-1]); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "conl_cost_fun_jac_hess", &capsule->conl_cost_fun_jac_hess[i-1]); - } -{%- elif cost.cost_type == "EXTERNAL" %} - for (int i = 1; i < N; i++) - { - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "ext_cost_fun", &capsule->ext_cost_fun[i-1]); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "ext_cost_fun_jac", &capsule->ext_cost_fun_jac[i-1]); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "ext_cost_fun_jac_hess", &capsule->ext_cost_fun_jac_hess[i-1]); - } -{%- endif %} - -{%- if cost.cost_type_e == "NONLINEAR_LS" %} - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_fun", &capsule->cost_y_e_fun); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_fun_jac", &capsule->cost_y_e_fun_jac_ut_xt); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_hess", &capsule->cost_y_e_hess); - -{%- elif cost.cost_type_e == "CONVEX_OVER_NONLINEAR" %} - - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "conl_cost_fun", &capsule->conl_cost_e_fun); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "conl_cost_fun_jac_hess", &capsule->conl_cost_e_fun_jac_hess); - -{%- elif cost.cost_type_e == "EXTERNAL" %} - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "ext_cost_fun", &capsule->ext_cost_e_fun); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "ext_cost_fun_jac", &capsule->ext_cost_e_fun_jac); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "ext_cost_fun_jac_hess", &capsule->ext_cost_e_fun_jac_hess); -{%- endif %} - - -{%- if dims.ns > 0 %} - // slacks - double* zlumem = calloc(4*NS, sizeof(double)); - double* Zl = zlumem+NS*0; - double* Zu = zlumem+NS*1; - double* zl = zlumem+NS*2; - double* zu = zlumem+NS*3; - // change only the non-zero elements: - {%- for j in range(end=dims.ns) %} - {%- if cost.Zl[j] != 0 %} - Zl[{{ j }}] = {{ cost.Zl[j] }}; - {%- endif %} - {%- endfor %} - - {%- for j in range(end=dims.ns) %} - {%- if cost.Zu[j] != 0 %} - Zu[{{ j }}] = {{ cost.Zu[j] }}; - {%- endif %} - {%- endfor %} - - {%- for j in range(end=dims.ns) %} - {%- if cost.zl[j] != 0 %} - zl[{{ j }}] = {{ cost.zl[j] }}; - {%- endif %} - {%- endfor %} - - {%- for j in range(end=dims.ns) %} - {%- if cost.zu[j] != 0 %} - zu[{{ j }}] = {{ cost.zu[j] }}; - {%- endif %} - {%- endfor %} - - for (int i = 0; i < N; i++) - { - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "Zl", Zl); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "Zu", Zu); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "zl", zl); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "zu", zu); - } - free(zlumem); -{%- endif %} - -{% if dims.ns_e > 0 %} - // slacks terminal - double* zluemem = calloc(4*NSN, sizeof(double)); - double* Zl_e = zluemem+NSN*0; - double* Zu_e = zluemem+NSN*1; - double* zl_e = zluemem+NSN*2; - double* zu_e = zluemem+NSN*3; - - // change only the non-zero elements: - {% for j in range(end=dims.ns_e) %} - {%- if cost.Zl_e[j] != 0 %} - Zl_e[{{ j }}] = {{ cost.Zl_e[j] }}; - {%- endif %} - {%- endfor %} - - {% for j in range(end=dims.ns_e) %} - {%- if cost.Zu_e[j] != 0 %} - Zu_e[{{ j }}] = {{ cost.Zu_e[j] }}; - {%- endif %} - {%- endfor %} - - {% for j in range(end=dims.ns_e) %} - {%- if cost.zl_e[j] != 0 %} - zl_e[{{ j }}] = {{ cost.zl_e[j] }}; - {%- endif %} - {%- endfor %} - - {% for j in range(end=dims.ns_e) %} - {%- if cost.zu_e[j] != 0 %} - zu_e[{{ j }}] = {{ cost.zu_e[j] }}; - {%- endif %} - {%- endfor %} - - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "Zl", Zl_e); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "Zu", Zu_e); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "zl", zl_e); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "zu", zu_e); - free(zluemem); -{%- endif %} - - /**** Constraints ****/ - - // bounds for initial stage -{%- if dims.nbx_0 > 0 %} - // x0 - int* idxbx0 = malloc(NBX0 * sizeof(int)); - {%- for i in range(end=dims.nbx_0) %} - idxbx0[{{ i }}] = {{ constraints.idxbx_0[i] }}; - {%- endfor %} - - double* lubx0 = calloc(2*NBX0, sizeof(double)); - double* lbx0 = lubx0; - double* ubx0 = lubx0 + NBX0; - // change only the non-zero elements: - {%- for i in range(end=dims.nbx_0) %} - {%- if constraints.lbx_0[i] != 0 %} - lbx0[{{ i }}] = {{ constraints.lbx_0[i] }}; - {%- endif %} - {%- if constraints.ubx_0[i] != 0 %} - ubx0[{{ i }}] = {{ constraints.ubx_0[i] }}; - {%- endif %} - {%- endfor %} - - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "idxbx", idxbx0); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "lbx", lbx0); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "ubx", ubx0); - free(idxbx0); - free(lubx0); -{%- endif %} - -{%- if dims.nbxe_0 > 0 %} - // idxbxe_0 - int* idxbxe_0 = malloc({{ dims.nbxe_0 }} * sizeof(int)); - {% for i in range(end=dims.nbxe_0) %} - idxbxe_0[{{ i }}] = {{ constraints.idxbxe_0[i] }}; - {%- endfor %} - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "idxbxe", idxbxe_0); - free(idxbxe_0); -{%- endif %} - - /* constraints that are the same for initial and intermediate */ -{%- if dims.nsbx > 0 %} -{# TODO: introduce nsbx0 & move this block down!! #} - // ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "idxsbx", idxsbx); - // ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "lsbx", lsbx); - // ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "usbx", usbx); - - // soft bounds on x - int* idxsbx = malloc(NSBX * sizeof(int)); - {%- for i in range(end=dims.nsbx) %} - idxsbx[{{ i }}] = {{ constraints.idxsbx[i] }}; - {%- endfor %} - - double* lusbx = calloc(2*NSBX, sizeof(double)); - double* lsbx = lusbx; - double* usbx = lusbx + NSBX; - {%- for i in range(end=dims.nsbx) %} - {%- if constraints.lsbx[i] != 0 %} - lsbx[{{ i }}] = {{ constraints.lsbx[i] }}; - {%- endif %} - {%- if constraints.usbx[i] != 0 %} - usbx[{{ i }}] = {{ constraints.usbx[i] }}; - {%- endif %} - {%- endfor %} - - for (int i = 1; i < N; i++) - { - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "idxsbx", idxsbx); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "lsbx", lsbx); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "usbx", usbx); - } - free(idxsbx); - free(lusbx); -{%- endif %} - - -{%- if dims.nbu > 0 %} - // u - int* idxbu = malloc(NBU * sizeof(int)); - {% for i in range(end=dims.nbu) %} - idxbu[{{ i }}] = {{ constraints.idxbu[i] }}; - {%- endfor %} - double* lubu = calloc(2*NBU, sizeof(double)); - double* lbu = lubu; - double* ubu = lubu + NBU; - {% for i in range(end=dims.nbu) %} - {%- if constraints.lbu[i] != 0 %} - lbu[{{ i }}] = {{ constraints.lbu[i] }}; - {%- endif %} - {%- if constraints.ubu[i] != 0 %} - ubu[{{ i }}] = {{ constraints.ubu[i] }}; - {%- endif %} - {%- endfor %} - - for (int i = 0; i < N; i++) - { - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "idxbu", idxbu); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "lbu", lbu); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "ubu", ubu); - } - free(idxbu); - free(lubu); -{%- endif %} - -{%- if dims.nsbu > 0 %} - // set up soft bounds for u - int* idxsbu = malloc(NSBU * sizeof(int)); - {% for i in range(end=dims.nsbu) %} - idxsbu[{{ i }}] = {{ constraints.idxsbu[i] }}; - {%- endfor %} - double* lusbu = calloc(2*NSBU, sizeof(double)); - double* lsbu = lusbu; - double* usbu = lusbu + NSBU; - {% for i in range(end=dims.nsbu) %} - {%- if constraints.lsbu[i] != 0 %} - lsbu[{{ i }}] = {{ constraints.lsbu[i] }}; - {%- endif %} - {%- if constraints.usbu[i] != 0 %} - usbu[{{ i }}] = {{ constraints.usbu[i] }}; - {%- endif %} - {%- endfor %} - for (int i = 0; i < N; i++) - { - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "idxsbu", idxsbu); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "lsbu", lsbu); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "usbu", usbu); - } - free(idxsbu); - free(lusbu); -{%- endif %} - -{% if dims.nsg > 0 %} - // set up soft bounds for general linear constraints - int* idxsg = malloc(NSG * sizeof(int)); - {% for i in range(end=dims.nsg) %} - idxsg[{{ i }}] = {{ constraints.idxsg[i] }}; - {%- endfor %} - double* lusg = calloc(2*NSG, sizeof(double)); - double* lsg = lusg; - double* usg = lusg + NSG; - {% for i in range(end=dims.nsg) %} - {%- if constraints.lsg[i] != 0 %} - lsg[{{ i }}] = {{ constraints.lsg[i] }}; - {%- endif %} - {%- if constraints.usg[i] != 0 %} - usg[{{ i }}] = {{ constraints.usg[i] }}; - {%- endif %} - {%- endfor %} - - for (int i = 0; i < N; i++) - { - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "idxsg", idxsg); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "lsg", lsg); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "usg", usg); - } - free(idxsg); - free(lusg); -{%- endif %} - -{% if dims.nsh > 0 %} - // set up soft bounds for nonlinear constraints - int* idxsh = malloc(NSH * sizeof(int)); - {% for i in range(end=dims.nsh) %} - idxsh[{{ i }}] = {{ constraints.idxsh[i] }}; - {%- endfor %} - double* lush = calloc(2*NSH, sizeof(double)); - double* lsh = lush; - double* ush = lush + NSH; - {% for i in range(end=dims.nsh) %} - {%- if constraints.lsh[i] != 0 %} - lsh[{{ i }}] = {{ constraints.lsh[i] }}; - {%- endif %} - {%- if constraints.ush[i] != 0 %} - ush[{{ i }}] = {{ constraints.ush[i] }}; - {%- endif %} - {%- endfor %} - - for (int i = 0; i < N; i++) - { - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "idxsh", idxsh); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "lsh", lsh); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "ush", ush); - } - free(idxsh); - free(lush); -{%- endif %} - -{% if dims.nsphi > 0 %} - // set up soft bounds for convex-over-nonlinear constraints - int* idxsphi = malloc(NSPHI * sizeof(int)); - {% for i in range(end=dims.nsphi) %} - idxsphi[{{ i }}] = {{ constraints.idxsphi[i] }}; - {%- endfor %} - double* lusphi = calloc(2*NSPHI, sizeof(double)); - double* lsphi = lusphi; - double* usphi = lusphi + NSPHI; - {% for i in range(end=dims.nsphi) %} - {%- if constraints.lsphi[i] != 0 %} - lsphi[{{ i }}] = {{ constraints.lsphi[i] }}; - {%- endif %} - {%- if constraints.usphi[i] != 0 %} - usphi[{{ i }}] = {{ constraints.usphi[i] }}; - {%- endif %} - {%- endfor %} - - for (int i = 0; i < N; i++) - { - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "idxsphi", idxsphi); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "lsphi", lsphi); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "usphi", usphi); - } - free(idxsphi); - free(lusphi); -{%- endif %} - -{% if dims.nbx > 0 %} - // x - int* idxbx = malloc(NBX * sizeof(int)); - {% for i in range(end=dims.nbx) %} - idxbx[{{ i }}] = {{ constraints.idxbx[i] }}; - {%- endfor %} - double* lubx = calloc(2*NBX, sizeof(double)); - double* lbx = lubx; - double* ubx = lubx + NBX; - {% for i in range(end=dims.nbx) %} - {%- if constraints.lbx[i] != 0 %} - lbx[{{ i }}] = {{ constraints.lbx[i] }}; - {%- endif %} - {%- if constraints.ubx[i] != 0 %} - ubx[{{ i }}] = {{ constraints.ubx[i] }}; - {%- endif %} - {%- endfor %} - - for (int i = 1; i < N; i++) - { - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "idxbx", idxbx); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "lbx", lbx); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "ubx", ubx); - } - free(idxbx); - free(lubx); -{%- endif %} - -{% if dims.ng > 0 %} - // set up general constraints for stage 0 to N-1 - double* D = calloc(NG*NU, sizeof(double)); - double* C = calloc(NG*NX, sizeof(double)); - double* lug = calloc(2*NG, sizeof(double)); - double* lg = lug; - double* ug = lug + NG; - - {% for j in range(end=dims.ng) -%} - {% for k in range(end=dims.nu) %} - {%- if constraints.D[j][k] != 0 %} - D[{{ j }}+NG * {{ k }}] = {{ constraints.D[j][k] }}; - {%- endif %} - {%- endfor %} - {%- endfor %} - - {% for j in range(end=dims.ng) -%} - {% for k in range(end=dims.nx) %} - {%- if constraints.C[j][k] != 0 %} - C[{{ j }}+NG * {{ k }}] = {{ constraints.C[j][k] }}; - {%- endif %} - {%- endfor %} - {%- endfor %} - - {% for i in range(end=dims.ng) %} - {%- if constraints.lg[i] != 0 %} - lg[{{ i }}] = {{ constraints.lg[i] }}; - {%- endif %} - {%- endfor %} - - {% for i in range(end=dims.ng) %} - {%- if constraints.ug[i] != 0 %} - ug[{{ i }}] = {{ constraints.ug[i] }}; - {%- endif %} - {%- endfor %} - - for (int i = 0; i < N; i++) - { - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "D", D); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "C", C); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "lg", lg); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "ug", ug); - } - free(D); - free(C); - free(lug); -{%- endif %} - -{% if dims.nh > 0 %} - // set up nonlinear constraints for stage 0 to N-1 - double* luh = calloc(2*NH, sizeof(double)); - double* lh = luh; - double* uh = luh + NH; - - {% for i in range(end=dims.nh) %} - {%- if constraints.lh[i] != 0 %} - lh[{{ i }}] = {{ constraints.lh[i] }}; - {%- endif %} - {%- endfor %} - - {% for i in range(end=dims.nh) %} - {%- if constraints.uh[i] != 0 %} - uh[{{ i }}] = {{ constraints.uh[i] }}; - {%- endif %} - {%- endfor %} - - for (int i = 0; i < N; i++) - { - // nonlinear constraints for stages 0 to N-1 - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "nl_constr_h_fun_jac", - &capsule->nl_constr_h_fun_jac[i]); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "nl_constr_h_fun", - &capsule->nl_constr_h_fun[i]); - {% if solver_options.hessian_approx == "EXACT" %} - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, - "nl_constr_h_fun_jac_hess", &capsule->nl_constr_h_fun_jac_hess[i]); - {% endif %} - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "lh", lh); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "uh", uh); - } - free(luh); -{%- endif %} - -{% if dims.nphi > 0 and constraints.constr_type == "BGP" %} - // set up convex-over-nonlinear constraints for stage 0 to N-1 - double* luphi = calloc(2*NPHI, sizeof(double)); - double* lphi = luphi; - double* uphi = luphi + NPHI; - {% for i in range(end=dims.nphi) %} - {%- if constraints.lphi[i] != 0 %} - lphi[{{ i }}] = {{ constraints.lphi[i] }}; - {%- endif %} - {%- endfor %} - - {% for i in range(end=dims.nphi) %} - {%- if constraints.uphi[i] != 0 %} - uphi[{{ i }}] = {{ constraints.uphi[i] }}; - {%- endif %} - {%- endfor %} - - for (int i = 0; i < N; i++) - { - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, - "nl_constr_phi_o_r_fun_phi_jac_ux_z_phi_hess_r_jac_ux", &capsule->phi_constraint[i]); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "lphi", lphi); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "uphi", uphi); - } - free(luphi); -{%- endif %} - - /* terminal constraints */ -{% if dims.nbx_e > 0 %} - // set up bounds for last stage - // x - int* idxbx_e = malloc(NBXN * sizeof(int)); - {% for i in range(end=dims.nbx_e) %} - idxbx_e[{{ i }}] = {{ constraints.idxbx_e[i] }}; - {%- endfor %} - double* lubx_e = calloc(2*NBXN, sizeof(double)); - double* lbx_e = lubx_e; - double* ubx_e = lubx_e + NBXN; - {% for i in range(end=dims.nbx_e) %} - {%- if constraints.lbx_e[i] != 0 %} - lbx_e[{{ i }}] = {{ constraints.lbx_e[i] }}; - {%- endif %} - {%- if constraints.ubx_e[i] != 0 %} - ubx_e[{{ i }}] = {{ constraints.ubx_e[i] }}; - {%- endif %} - {%- endfor %} - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "idxbx", idxbx_e); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "lbx", lbx_e); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "ubx", ubx_e); - free(idxbx_e); - free(lubx_e); -{%- endif %} - -{% if dims.nsg_e > 0 %} - // set up soft bounds for general linear constraints - int* idxsg_e = calloc(NSGN, sizeof(int)); - {% for i in range(end=dims.nsg_e) %} - idxsg_e[{{ i }}] = {{ constraints.idxsg_e[i] }}; - {%- endfor %} - double* lusg_e = calloc(2*NSGN, sizeof(double)); - double* lsg_e = lusg_e; - double* usg_e = lusg_e + NSGN; - {% for i in range(end=dims.nsg_e) %} - {%- if constraints.lsg_e[i] != 0 %} - lsg_e[{{ i }}] = {{ constraints.lsg_e[i] }}; - {%- endif %} - {%- if constraints.usg_e[i] != 0 %} - usg_e[{{ i }}] = {{ constraints.usg_e[i] }}; - {%- endif %} - {%- endfor %} - - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "idxsg", idxsg_e); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "lsg", lsg_e); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "usg", usg_e); - free(idxsg_e); - free(lusg_e); -{%- endif %} - -{% if dims.nsh_e > 0 %} - // set up soft bounds for nonlinear constraints - int* idxsh_e = malloc(NSHN * sizeof(int)); - {% for i in range(end=dims.nsh_e) %} - idxsh_e[{{ i }}] = {{ constraints.idxsh_e[i] }}; - {%- endfor %} - double* lush_e = calloc(2*NSHN, sizeof(double)); - double* lsh_e = lush_e; - double* ush_e = lush_e + NSHN; - {% for i in range(end=dims.nsh_e) %} - {%- if constraints.lsh_e[i] != 0 %} - lsh_e[{{ i }}] = {{ constraints.lsh_e[i] }}; - {%- endif %} - {%- if constraints.ush_e[i] != 0 %} - ush_e[{{ i }}] = {{ constraints.ush_e[i] }}; - {%- endif %} - {%- endfor %} - - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "idxsh", idxsh_e); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "lsh", lsh_e); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "ush", ush_e); - free(idxsh_e); - free(lush_e); -{%- endif %} - -{% if dims.nsphi_e > 0 %} - // set up soft bounds for convex-over-nonlinear constraints - int* idxsphi_e = malloc(NSPHIN * sizeof(int)); - {% for i in range(end=dims.nsphi_e) %} - idxsphi_e[{{ i }}] = {{ constraints.idxsphi_e[i] }}; - {%- endfor %} - double* lusphi_e = calloc(2*NSPHIN, sizeof(double)); - double* lsphi_e = lusphi_e; - double* usphi_e = lusphi_e + NSPHIN; - {% for i in range(end=dims.nsphi_e) %} - {%- if constraints.lsphi_e[i] != 0 %} - lsphi_e[{{ i }}] = {{ constraints.lsphi_e[i] }}; - {%- endif %} - {%- if constraints.usphi_e[i] != 0 %} - usphi_e[{{ i }}] = {{ constraints.usphi_e[i] }}; - {%- endif %} - {%- endfor %} - - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "idxsphi", idxsphi_e); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "lsphi", lsphi_e); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "usphi", usphi_e); - free(idxsphi_e); - free(lusphi_e); -{%- endif %} - -{% if dims.nsbx_e > 0 %} - // soft bounds on x - int* idxsbx_e = malloc(NSBXN * sizeof(int)); - {% for i in range(end=dims.nsbx_e) %} - idxsbx_e[{{ i }}] = {{ constraints.idxsbx_e[i] }}; - {%- endfor %} - double* lusbx_e = calloc(2*NSBXN, sizeof(double)); - double* lsbx_e = lusbx_e; - double* usbx_e = lusbx_e + NSBXN; - {% for i in range(end=dims.nsbx_e) %} - {%- if constraints.lsbx_e[i] != 0 %} - lsbx_e[{{ i }}] = {{ constraints.lsbx_e[i] }}; - {%- endif %} - {%- if constraints.usbx_e[i] != 0 %} - usbx_e[{{ i }}] = {{ constraints.usbx_e[i] }}; - {%- endif %} - {%- endfor %} - - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "idxsbx", idxsbx_e); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "lsbx", lsbx_e); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "usbx", usbx_e); - free(idxsbx_e); - free(lusbx_e); -{% endif %} - -{% if dims.ng_e > 0 %} - // set up general constraints for last stage - double* C_e = calloc(NGN*NX, sizeof(double)); - double* lug_e = calloc(2*NGN, sizeof(double)); - double* lg_e = lug_e; - double* ug_e = lug_e + NGN; - - {% for j in range(end=dims.ng_e) %} - {%- for k in range(end=dims.nx) %} - {%- if constraints.C_e[j][k] != 0 %} - C_e[{{ j }}+NGN * {{ k }}] = {{ constraints.C_e[j][k] }}; - {%- endif %} - {%- endfor %} - {%- endfor %} - - {% for i in range(end=dims.ng_e) %} - {%- if constraints.lg_e[i] != 0 %} - lg_e[{{ i }}] = {{ constraints.lg_e[i] }}; - {%- endif %} - {%- if constraints.ug_e[i] != 0 %} - ug_e[{{ i }}] = {{ constraints.ug_e[i] }}; - {%- endif %} - {%- endfor %} - - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "C", C_e); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "lg", lg_e); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "ug", ug_e); - free(C_e); - free(lug_e); -{%- endif %} - -{% if dims.nh_e > 0 %} - // set up nonlinear constraints for last stage - double* luh_e = calloc(2*NHN, sizeof(double)); - double* lh_e = luh_e; - double* uh_e = luh_e + NHN; - {% for i in range(end=dims.nh_e) %} - {%- if constraints.lh_e[i] != 0 %} - lh_e[{{ i }}] = {{ constraints.lh_e[i] }}; - {%- endif %} - {%- endfor %} - - {% for i in range(end=dims.nh_e) %} - {%- if constraints.uh_e[i] != 0 %} - uh_e[{{ i }}] = {{ constraints.uh_e[i] }}; - {%- endif %} - {%- endfor %} - - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "nl_constr_h_fun_jac", &capsule->nl_constr_h_e_fun_jac); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "nl_constr_h_fun", &capsule->nl_constr_h_e_fun); - {% if solver_options.hessian_approx == "EXACT" %} - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "nl_constr_h_fun_jac_hess", - &capsule->nl_constr_h_e_fun_jac_hess); - {% endif %} - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "lh", lh_e); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "uh", uh_e); - free(luh_e); -{%- endif %} - -{% if dims.nphi_e > 0 and constraints.constr_type_e == "BGP" %} - // set up convex-over-nonlinear constraints for last stage - double* luphi_e = calloc(2*NPHIN, sizeof(double)); - double* lphi_e = luphi_e; - double* uphi_e = luphi_e + NPHIN; - {% for i in range(end=dims.nphi_e) %} - {%- if constraints.lphi_e[i] != 0 %} - lphi_e[{{ i }}] = {{ constraints.lphi_e[i] }}; - {%- endif %} - {%- if constraints.uphi_e[i] != 0 %} - uphi_e[{{ i }}] = {{ constraints.uphi_e[i] }}; - {%- endif %} - {%- endfor %} - - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "lphi", lphi_e); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "uphi", uphi_e); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, - "nl_constr_phi_o_r_fun_phi_jac_ux_z_phi_hess_r_jac_ux", &capsule->phi_e_constraint); - free(luphi_e); -{% endif %} -} - - -/** - * Internal function for {{ model.name }}_acados_create: step 6 - */ -void {{ model.name }}_acados_create_6_set_opts({{ model.name }}_solver_capsule* capsule) -{ - const int N = capsule->nlp_solver_plan->N; - ocp_nlp_config* nlp_config = capsule->nlp_config; - void *nlp_opts = capsule->nlp_opts; - - /************************************************ - * opts - ************************************************/ - -{% if solver_options.hessian_approx == "EXACT" %} - int nlp_solver_exact_hessian = 1; - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "exact_hess", &nlp_solver_exact_hessian); - - int exact_hess_dyn = {{ solver_options.exact_hess_dyn }}; - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "exact_hess_dyn", &exact_hess_dyn); - - int exact_hess_cost = {{ solver_options.exact_hess_cost }}; - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "exact_hess_cost", &exact_hess_cost); - - int exact_hess_constr = {{ solver_options.exact_hess_constr }}; - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "exact_hess_constr", &exact_hess_constr); -{%- endif -%} - -{%- if solver_options.globalization == "FIXED_STEP" %} - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "globalization", "fixed_step"); -{%- elif solver_options.globalization == "MERIT_BACKTRACKING" %} - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "globalization", "merit_backtracking"); - - double alpha_min = {{ solver_options.alpha_min }}; - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "alpha_min", &alpha_min); - - double alpha_reduction = {{ solver_options.alpha_reduction }}; - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "alpha_reduction", &alpha_reduction); - - int line_search_use_sufficient_descent = {{ solver_options.line_search_use_sufficient_descent }}; - ocp_nlp_solver_opts_set(nlp_config, capsule->nlp_opts, "line_search_use_sufficient_descent", &line_search_use_sufficient_descent); - - int globalization_use_SOC = {{ solver_options.globalization_use_SOC }}; - ocp_nlp_solver_opts_set(nlp_config, capsule->nlp_opts, "globalization_use_SOC", &globalization_use_SOC); - - double eps_sufficient_descent = {{ solver_options.eps_sufficient_descent }}; - ocp_nlp_solver_opts_set(nlp_config, capsule->nlp_opts, "eps_sufficient_descent", &eps_sufficient_descent); -{%- endif -%} - int full_step_dual = {{ solver_options.full_step_dual }}; - ocp_nlp_solver_opts_set(nlp_config, capsule->nlp_opts, "full_step_dual", &full_step_dual); - -{%- if dims.nz > 0 %} - // TODO: these options are lower level -> should be encapsulated! maybe through hessian approx option. - bool output_z_val = true; - bool sens_algebraic_val = true; - - for (int i = 0; i < N; i++) - ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_output_z", &output_z_val); - for (int i = 0; i < N; i++) - ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_sens_algebraic", &sens_algebraic_val); -{%- endif %} - -{%- if solver_options.integrator_type != "DISCRETE" %} - - // set collocation type (relevant for implicit integrators) - sim_collocation_type collocation_type = {{ solver_options.collocation_type }}; - for (int i = 0; i < N; i++) - ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_collocation_type", &collocation_type); - - // set up sim_method_num_steps - {%- set all_equal = true %} - {%- set val = solver_options.sim_method_num_steps[0] %} - {%- for j in range(start=1, end=dims.N) %} - {%- if val != solver_options.sim_method_num_steps[j] %} - {%- set_global all_equal = false %} - {%- break %} - {%- endif %} - {%- endfor %} - - {%- if all_equal == true %} - // all sim_method_num_steps are identical - int sim_method_num_steps = {{ solver_options.sim_method_num_steps[0] }}; - for (int i = 0; i < N; i++) - ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_num_steps", &sim_method_num_steps); - {%- else %} - // sim_method_num_steps are different - int* sim_method_num_steps = malloc(N*sizeof(int)); - {%- for j in range(end=dims.N) %} - sim_method_num_steps[{{ j }}] = {{ solver_options.sim_method_num_steps[j] }}; - {%- endfor %} - - for (int i = 0; i < N; i++) - ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_num_steps", &sim_method_num_steps[i]); - free(sim_method_num_steps); - {%- endif %} - - // set up sim_method_num_stages - {%- set all_equal = true %} - {%- set val = solver_options.sim_method_num_stages[0] %} - {%- for j in range(start=1, end=dims.N) %} - {%- if val != solver_options.sim_method_num_stages[j] %} - {%- set_global all_equal = false %} - {%- break %} - {%- endif %} - {%- endfor %} - - {%- if all_equal == true %} - // all sim_method_num_stages are identical - int sim_method_num_stages = {{ solver_options.sim_method_num_stages[0] }}; - for (int i = 0; i < N; i++) - ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_num_stages", &sim_method_num_stages); - {%- else %} - int* sim_method_num_stages = malloc(N*sizeof(int)); - {%- for j in range(end=dims.N) %} - sim_method_num_stages[{{ j }}] = {{ solver_options.sim_method_num_stages[j] }}; - {%- endfor %} - - for (int i = 0; i < N; i++) - ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_num_stages", &sim_method_num_stages[i]); - free(sim_method_num_stages); - {%- endif %} - - int newton_iter_val = {{ solver_options.sim_method_newton_iter }}; - for (int i = 0; i < N; i++) - ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_newton_iter", &newton_iter_val); - - - // set up sim_method_jac_reuse - {%- set all_equal = true %} - {%- set val = solver_options.sim_method_jac_reuse[0] %} - {%- for j in range(start=1, end=dims.N) %} - {%- if val != solver_options.sim_method_jac_reuse[j] %} - {%- set_global all_equal = false %} - {%- break %} - {%- endif %} - {%- endfor %} - {%- if all_equal == true %} - bool tmp_bool = (bool) {{ solver_options.sim_method_jac_reuse[0] }}; - for (int i = 0; i < N; i++) - ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_jac_reuse", &tmp_bool); - {%- else %} - bool* sim_method_jac_reuse = malloc(N*sizeof(bool)); - {%- for j in range(end=dims.N) %} - sim_method_jac_reuse[{{ j }}] = (bool){{ solver_options.sim_method_jac_reuse[j] }}; - {%- endfor %} - - for (int i = 0; i < N; i++) - ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_jac_reuse", &sim_method_jac_reuse[i]); - free(sim_method_jac_reuse); - {%- endif %} - -{%- endif %} - - double nlp_solver_step_length = {{ solver_options.nlp_solver_step_length }}; - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "step_length", &nlp_solver_step_length); - - {%- if solver_options.nlp_solver_warm_start_first_qp %} - int nlp_solver_warm_start_first_qp = {{ solver_options.nlp_solver_warm_start_first_qp }}; - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "warm_start_first_qp", &nlp_solver_warm_start_first_qp); - {%- endif %} - - double levenberg_marquardt = {{ solver_options.levenberg_marquardt }}; - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "levenberg_marquardt", &levenberg_marquardt); - - /* options QP solver */ -{%- if solver_options.qp_solver is starting_with("PARTIAL_CONDENSING") %} - int qp_solver_cond_N; - - {% if solver_options.qp_solver_cond_N -%} - const int qp_solver_cond_N_ori = {{ solver_options.qp_solver_cond_N }}; - qp_solver_cond_N = N < qp_solver_cond_N_ori ? N : qp_solver_cond_N_ori; // use the minimum value here - {%- else %} - // NOTE: there is no condensing happening here! - qp_solver_cond_N = N; - {%- endif %} - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_cond_N", &qp_solver_cond_N); -{%- endif %} - - int nlp_solver_ext_qp_res = {{ solver_options.nlp_solver_ext_qp_res }}; - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "ext_qp_res", &nlp_solver_ext_qp_res); - -{%- if solver_options.qp_solver is containing("HPIPM") %} - // set HPIPM mode: should be done before setting other QP solver options - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_hpipm_mode", "{{ solver_options.hpipm_mode }}"); -{%- endif %} - -{% if solver_options.nlp_solver_type == "SQP" %} - // set SQP specific options - double nlp_solver_tol_stat = {{ solver_options.nlp_solver_tol_stat }}; - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "tol_stat", &nlp_solver_tol_stat); - - double nlp_solver_tol_eq = {{ solver_options.nlp_solver_tol_eq }}; - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "tol_eq", &nlp_solver_tol_eq); - - double nlp_solver_tol_ineq = {{ solver_options.nlp_solver_tol_ineq }}; - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "tol_ineq", &nlp_solver_tol_ineq); - - double nlp_solver_tol_comp = {{ solver_options.nlp_solver_tol_comp }}; - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "tol_comp", &nlp_solver_tol_comp); - - int nlp_solver_max_iter = {{ solver_options.nlp_solver_max_iter }}; - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "max_iter", &nlp_solver_max_iter); - - int initialize_t_slacks = {{ solver_options.initialize_t_slacks }}; - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "initialize_t_slacks", &initialize_t_slacks); -{%- endif %} - - int qp_solver_iter_max = {{ solver_options.qp_solver_iter_max }}; - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_iter_max", &qp_solver_iter_max); - -{# NOTE: qp_solver tolerances must be set after NLP ones, since the setter for NLP tolerances sets the QP tolerances to the sam values. #} - {%- if solver_options.qp_solver_tol_stat %} - double qp_solver_tol_stat = {{ solver_options.qp_solver_tol_stat }}; - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_tol_stat", &qp_solver_tol_stat); - {%- endif -%} - - {%- if solver_options.qp_solver_tol_eq %} - double qp_solver_tol_eq = {{ solver_options.qp_solver_tol_eq }}; - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_tol_eq", &qp_solver_tol_eq); - {%- endif -%} - - {%- if solver_options.qp_solver_tol_ineq %} - double qp_solver_tol_ineq = {{ solver_options.qp_solver_tol_ineq }}; - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_tol_ineq", &qp_solver_tol_ineq); - {%- endif -%} - - {%- if solver_options.qp_solver_tol_comp %} - double qp_solver_tol_comp = {{ solver_options.qp_solver_tol_comp }}; - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_tol_comp", &qp_solver_tol_comp); - {%- endif -%} - - {%- if solver_options.qp_solver_warm_start %} - int qp_solver_warm_start = {{ solver_options.qp_solver_warm_start }}; - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_warm_start", &qp_solver_warm_start); - {%- endif -%} - - int print_level = {{ solver_options.print_level }}; - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "print_level", &print_level); - -{%- if solver_options.qp_solver is containing('PARTIAL_CONDENSING') %} - int qp_solver_cond_ric_alg = {{ solver_options.qp_solver_cond_ric_alg }}; - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_cond_ric_alg", &qp_solver_cond_ric_alg); -{% endif %} - -{%- if solver_options.qp_solver == 'PARTIAL_CONDENSING_HPIPM' %} - int qp_solver_ric_alg = {{ solver_options.qp_solver_ric_alg }}; - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_ric_alg", &qp_solver_ric_alg); -{% endif %} - - int ext_cost_num_hess = {{ solver_options.ext_cost_num_hess }}; -{%- if cost.cost_type == "EXTERNAL" %} - for (int i = 0; i < N; i++) - { - ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "cost_numerical_hessian", &ext_cost_num_hess); - } -{%- endif %} -{%- if cost.cost_type_e == "EXTERNAL" %} - ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, N, "cost_numerical_hessian", &ext_cost_num_hess); -{%- endif %} -} - - -/** - * Internal function for {{ model.name }}_acados_create: step 7 - */ -void {{ model.name }}_acados_create_7_set_nlp_out({{ model.name }}_solver_capsule* capsule) -{ - const int N = capsule->nlp_solver_plan->N; - ocp_nlp_config* nlp_config = capsule->nlp_config; - ocp_nlp_dims* nlp_dims = capsule->nlp_dims; - ocp_nlp_out* nlp_out = capsule->nlp_out; - - // initialize primal solution - double* xu0 = calloc(NX+NU, sizeof(double)); - double* x0 = xu0; -{% if dims.nbx_0 == dims.nx %} - // initialize with x0 - {% for item in constraints.lbx_0 %} - {%- if item != 0 %} - x0[{{ loop.index0 }}] = {{ item }}; - {%- endif %} - {%- endfor %} -{% else %} - // initialize with zeros -{%- endif %} - - double* u0 = xu0 + NX; - - for (int i = 0; i < N; i++) - { - // x0 - ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "x", x0); - // u0 - ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "u", u0); - } - ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, N, "x", x0); - free(xu0); -} - - -/** - * Internal function for {{ model.name }}_acados_create: step 8 - */ -//void {{ model.name }}_acados_create_8_create_solver({{ model.name }}_solver_capsule* capsule) -//{ -// capsule->nlp_solver = ocp_nlp_solver_create(capsule->nlp_config, capsule->nlp_dims, capsule->nlp_opts); -//} - -/** - * Internal function for {{ model.name }}_acados_create: step 9 - */ -int {{ model.name }}_acados_create_9_precompute({{ model.name }}_solver_capsule* capsule) { - int status = ocp_nlp_precompute(capsule->nlp_solver, capsule->nlp_in, capsule->nlp_out); - - if (status != ACADOS_SUCCESS) { - printf("\nocp_nlp_precompute failed!\n\n"); - exit(1); - } - - return status; -} - - -int {{ model.name }}_acados_create_with_discretization({{ model.name }}_solver_capsule* capsule, int N, double* new_time_steps) -{ - // If N does not match the number of shooting intervals used for code generation, new_time_steps must be given. - if (N != {{ model.name | upper }}_N && !new_time_steps) { - fprintf(stderr, "{{ model.name }}_acados_create_with_discretization: new_time_steps is NULL " \ - "but the number of shooting intervals (= %d) differs from the number of " \ - "shooting intervals (= %d) during code generation! Please provide a new vector of time_stamps!\n", \ - N, {{ model.name | upper }}_N); - return 1; - } - - // number of expected runtime parameters - capsule->nlp_np = NP; - - // 1) create and set nlp_solver_plan; create nlp_config - capsule->nlp_solver_plan = ocp_nlp_plan_create(N); - {{ model.name }}_acados_create_1_set_plan(capsule->nlp_solver_plan, N); - capsule->nlp_config = ocp_nlp_config_create(*capsule->nlp_solver_plan); - - // 3) create and set dimensions - capsule->nlp_dims = {{ model.name }}_acados_create_2_create_and_set_dimensions(capsule); - {{ model.name }}_acados_create_3_create_and_set_functions(capsule); - - // 4) set default parameters in functions - {{ model.name }}_acados_create_4_set_default_parameters(capsule); - - // 5) create and set nlp_in - capsule->nlp_in = ocp_nlp_in_create(capsule->nlp_config, capsule->nlp_dims); - {{ model.name }}_acados_create_5_set_nlp_in(capsule, N, new_time_steps); - - // 6) create and set nlp_opts - capsule->nlp_opts = ocp_nlp_solver_opts_create(capsule->nlp_config, capsule->nlp_dims); - {{ model.name }}_acados_create_6_set_opts(capsule); - - // 7) create and set nlp_out - // 7.1) nlp_out - capsule->nlp_out = ocp_nlp_out_create(capsule->nlp_config, capsule->nlp_dims); - // 7.2) sens_out - capsule->sens_out = ocp_nlp_out_create(capsule->nlp_config, capsule->nlp_dims); - {{ model.name }}_acados_create_7_set_nlp_out(capsule); - - // 8) create solver - capsule->nlp_solver = ocp_nlp_solver_create(capsule->nlp_config, capsule->nlp_dims, capsule->nlp_opts); - //{{ model.name }}_acados_create_8_create_solver(capsule); - - // 9) do precomputations - int status = {{ model.name }}_acados_create_9_precompute(capsule); - - {%- if custom_update_filename != "" %} - // Initialize custom update function - custom_update_init_function(capsule); - {%- endif %} - - return status; -} - -/** - * This function is for updating an already initialized solver with a different number of qp_cond_N. It is useful for code reuse after code export. - */ -int {{ model.name }}_acados_update_qp_solver_cond_N({{ model.name }}_solver_capsule* capsule, int qp_solver_cond_N) -{ -{%- if solver_options.qp_solver is starting_with("PARTIAL_CONDENSING") %} - // 1) destroy solver - ocp_nlp_solver_destroy(capsule->nlp_solver); - - // 2) set new value for "qp_cond_N" - const int N = capsule->nlp_solver_plan->N; - if(qp_solver_cond_N > N) - printf("Warning: qp_solver_cond_N = %d > N = %d\n", qp_solver_cond_N, N); - ocp_nlp_solver_opts_set(capsule->nlp_config, capsule->nlp_opts, "qp_cond_N", &qp_solver_cond_N); - - // 3) continue with the remaining steps from {{ model.name }}_acados_create_with_discretization(...): - // -> 8) create solver - capsule->nlp_solver = ocp_nlp_solver_create(capsule->nlp_config, capsule->nlp_dims, capsule->nlp_opts); - - // -> 9) do precomputations - int status = {{ model.name }}_acados_create_9_precompute(capsule); - return status; -{%- else %} - printf("\nacados_update_qp_solver_cond_N() failed, since no partial condensing solver is used!\n\n"); - // Todo: what is an adequate behavior here? - exit(1); - return -1; -{%- endif %} -} - - -int {{ model.name }}_acados_reset({{ model.name }}_solver_capsule* capsule, int reset_qp_solver_mem) -{ - - // set initialization to all zeros -{# TODO: use guess values / initial state value from json instead?! #} - const int N = capsule->nlp_solver_plan->N; - ocp_nlp_config* nlp_config = capsule->nlp_config; - ocp_nlp_dims* nlp_dims = capsule->nlp_dims; - ocp_nlp_out* nlp_out = capsule->nlp_out; - ocp_nlp_in* nlp_in = capsule->nlp_in; - ocp_nlp_solver* nlp_solver = capsule->nlp_solver; - - double* buffer = calloc(NX+NU+NZ+2*NS+2*NSN+NBX+NBU+NG+NH+NPHI+NBX0+NBXN+NHN+NPHIN+NGN, sizeof(double)); - - for(int i=0; i reset memory - int qp_status; - ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "qp_status", &qp_status); - if (reset_qp_solver_mem || (qp_status == 3)) - { - // printf("\nin reset qp_status %d -> resetting QP memory\n", qp_status); - ocp_nlp_solver_reset_qp_memory(nlp_solver, nlp_in, nlp_out); - } -{%- endif %} - - free(buffer); - return 0; -} - - - - -int {{ model.name }}_acados_update_params({{ model.name }}_solver_capsule* capsule, int stage, double *p, int np) -{ - int solver_status = 0; - - int casadi_np = {{ dims.np }}; - if (casadi_np != np) { - printf("acados_update_params: trying to set %i parameters for external functions." - " External function has %i parameters. Exiting.\n", np, casadi_np); - exit(1); - } - - const int N = capsule->nlp_solver_plan->N; - if (stage < N && stage >= 0) - { - {%- if solver_options.integrator_type == "IRK" %} - capsule->impl_dae_fun[stage].set_param(capsule->impl_dae_fun+stage, p); - capsule->impl_dae_fun_jac_x_xdot_z[stage].set_param(capsule->impl_dae_fun_jac_x_xdot_z+stage, p); - capsule->impl_dae_jac_x_xdot_u_z[stage].set_param(capsule->impl_dae_jac_x_xdot_u_z+stage, p); - - {%- if solver_options.hessian_approx == "EXACT" %} - capsule->impl_dae_hess[stage].set_param(capsule->impl_dae_hess+stage, p); - {%- endif %} - {% elif solver_options.integrator_type == "LIFTED_IRK" %} - capsule->impl_dae_fun[stage].set_param(capsule->impl_dae_fun+stage, p); - capsule->impl_dae_fun_jac_x_xdot_u[stage].set_param(capsule->impl_dae_fun_jac_x_xdot_u+stage, p); - {% elif solver_options.integrator_type == "ERK" %} - capsule->forw_vde_casadi[stage].set_param(capsule->forw_vde_casadi+stage, p); - capsule->expl_ode_fun[stage].set_param(capsule->expl_ode_fun+stage, p); - - {%- if solver_options.hessian_approx == "EXACT" %} - capsule->hess_vde_casadi[stage].set_param(capsule->hess_vde_casadi+stage, p); - {%- endif %} - {% elif solver_options.integrator_type == "GNSF" %} - {% if model.gnsf.purely_linear != 1 %} - capsule->gnsf_phi_fun[stage].set_param(capsule->gnsf_phi_fun+stage, p); - capsule->gnsf_phi_fun_jac_y[stage].set_param(capsule->gnsf_phi_fun_jac_y+stage, p); - capsule->gnsf_phi_jac_y_uhat[stage].set_param(capsule->gnsf_phi_jac_y_uhat+stage, p); - {% if model.gnsf.nontrivial_f_LO == 1 %} - capsule->gnsf_f_lo_jac_x1_x1dot_u_z[stage].set_param(capsule->gnsf_f_lo_jac_x1_x1dot_u_z+stage, p); - {%- endif %} - {%- endif %} - {% elif solver_options.integrator_type == "DISCRETE" %} - capsule->discr_dyn_phi_fun[stage].set_param(capsule->discr_dyn_phi_fun+stage, p); - capsule->discr_dyn_phi_fun_jac_ut_xt[stage].set_param(capsule->discr_dyn_phi_fun_jac_ut_xt+stage, p); - {%- if solver_options.hessian_approx == "EXACT" %} - capsule->discr_dyn_phi_fun_jac_ut_xt_hess[stage].set_param(capsule->discr_dyn_phi_fun_jac_ut_xt_hess+stage, p); - {% endif %} - {%- endif %}{# integrator_type #} - - // constraints - {% if constraints.constr_type == "BGP" %} - capsule->phi_constraint[stage].set_param(capsule->phi_constraint+stage, p); - {% elif constraints.constr_type == "BGH" and dims.nh > 0 %} - capsule->nl_constr_h_fun_jac[stage].set_param(capsule->nl_constr_h_fun_jac+stage, p); - capsule->nl_constr_h_fun[stage].set_param(capsule->nl_constr_h_fun+stage, p); - {%- if solver_options.hessian_approx == "EXACT" %} - capsule->nl_constr_h_fun_jac_hess[stage].set_param(capsule->nl_constr_h_fun_jac_hess+stage, p); - {%- endif %} - {%- endif %} - - // cost - if (stage == 0) - { - {%- if cost.cost_type_0 == "NONLINEAR_LS" %} - capsule->cost_y_0_fun.set_param(&capsule->cost_y_0_fun, p); - capsule->cost_y_0_fun_jac_ut_xt.set_param(&capsule->cost_y_0_fun_jac_ut_xt, p); - capsule->cost_y_0_hess.set_param(&capsule->cost_y_0_hess, p); - {%- elif cost.cost_type_0 == "CONVEX_OVER_NONLINEAR" %} - capsule->conl_cost_0_fun.set_param(&capsule->conl_cost_0_fun, p); - capsule->conl_cost_0_fun_jac_hess.set_param(&capsule->conl_cost_0_fun_jac_hess, p); - {%- elif cost.cost_type_0 == "EXTERNAL" %} - capsule->ext_cost_0_fun.set_param(&capsule->ext_cost_0_fun, p); - capsule->ext_cost_0_fun_jac.set_param(&capsule->ext_cost_0_fun_jac, p); - capsule->ext_cost_0_fun_jac_hess.set_param(&capsule->ext_cost_0_fun_jac_hess, p); - {% endif %} - } - else // 0 < stage < N - { - {%- if cost.cost_type == "NONLINEAR_LS" %} - capsule->cost_y_fun[stage-1].set_param(capsule->cost_y_fun+stage-1, p); - capsule->cost_y_fun_jac_ut_xt[stage-1].set_param(capsule->cost_y_fun_jac_ut_xt+stage-1, p); - capsule->cost_y_hess[stage-1].set_param(capsule->cost_y_hess+stage-1, p); - {%- elif cost.cost_type == "CONVEX_OVER_NONLINEAR" %} - capsule->conl_cost_fun[stage-1].set_param(capsule->conl_cost_fun+stage-1, p); - capsule->conl_cost_fun_jac_hess[stage-1].set_param(capsule->conl_cost_fun_jac_hess+stage-1, p); - {%- elif cost.cost_type == "EXTERNAL" %} - capsule->ext_cost_fun[stage-1].set_param(capsule->ext_cost_fun+stage-1, p); - capsule->ext_cost_fun_jac[stage-1].set_param(capsule->ext_cost_fun_jac+stage-1, p); - capsule->ext_cost_fun_jac_hess[stage-1].set_param(capsule->ext_cost_fun_jac_hess+stage-1, p); - {%- endif %} - } - } - - else // stage == N - { - // terminal shooting node has no dynamics - // cost - {%- if cost.cost_type_e == "NONLINEAR_LS" %} - capsule->cost_y_e_fun.set_param(&capsule->cost_y_e_fun, p); - capsule->cost_y_e_fun_jac_ut_xt.set_param(&capsule->cost_y_e_fun_jac_ut_xt, p); - capsule->cost_y_e_hess.set_param(&capsule->cost_y_e_hess, p); - {%- elif cost.cost_type_e == "CONVEX_OVER_NONLINEAR" %} - capsule->conl_cost_e_fun.set_param(&capsule->conl_cost_e_fun, p); - capsule->conl_cost_e_fun_jac_hess.set_param(&capsule->conl_cost_e_fun_jac_hess, p); - {%- elif cost.cost_type_e == "EXTERNAL" %} - capsule->ext_cost_e_fun.set_param(&capsule->ext_cost_e_fun, p); - capsule->ext_cost_e_fun_jac.set_param(&capsule->ext_cost_e_fun_jac, p); - capsule->ext_cost_e_fun_jac_hess.set_param(&capsule->ext_cost_e_fun_jac_hess, p); - {% endif %} - // constraints - {% if constraints.constr_type_e == "BGP" %} - capsule->phi_e_constraint.set_param(&capsule->phi_e_constraint, p); - {% elif constraints.constr_type_e == "BGH" and dims.nh_e > 0 %} - capsule->nl_constr_h_e_fun_jac.set_param(&capsule->nl_constr_h_e_fun_jac, p); - capsule->nl_constr_h_e_fun.set_param(&capsule->nl_constr_h_e_fun, p); - {%- if solver_options.hessian_approx == "EXACT" %} - capsule->nl_constr_h_e_fun_jac_hess.set_param(&capsule->nl_constr_h_e_fun_jac_hess, p); - {%- endif %} - {% endif %} - } - - return solver_status; -} - - -int {{ model.name }}_acados_update_params_sparse({{ model.name }}_solver_capsule * capsule, int stage, int *idx, double *p, int n_update) -{ - int solver_status = 0; - - int casadi_np = {{ dims.np }}; - if (casadi_np < n_update) { - printf("{{ model.name }}_acados_update_params_sparse: trying to set %d parameters for external functions." - " External function has %d parameters. Exiting.\n", n_update, casadi_np); - exit(1); - } - // for (int i = 0; i < n_update; i++) - // { - // if (idx[i] > casadi_np) { - // printf("{{ model.name }}_acados_update_params_sparse: attempt to set parameters with index %d, while" - // " external functions only has %d parameters. Exiting.\n", idx[i], casadi_np); - // exit(1); - // } - // printf("param %d value %e\n", idx[i], p[i]); - // } - -{%- if dims.np > 0 %} - const int N = capsule->nlp_solver_plan->N; - if (stage < N && stage >= 0) - { - {%- if solver_options.integrator_type == "IRK" %} - capsule->impl_dae_fun[stage].set_param_sparse(capsule->impl_dae_fun+stage, n_update, idx, p); - capsule->impl_dae_fun_jac_x_xdot_z[stage].set_param_sparse(capsule->impl_dae_fun_jac_x_xdot_z+stage, n_update, idx, p); - capsule->impl_dae_jac_x_xdot_u_z[stage].set_param_sparse(capsule->impl_dae_jac_x_xdot_u_z+stage, n_update, idx, p); - - {%- if solver_options.hessian_approx == "EXACT" %} - capsule->impl_dae_hess[stage].set_param_sparse(capsule->impl_dae_hess+stage, n_update, idx, p); - {%- endif %} - {% elif solver_options.integrator_type == "LIFTED_IRK" %} - capsule->impl_dae_fun[stage].set_param_sparse(capsule->impl_dae_fun+stage, n_update, idx, p); - capsule->impl_dae_fun_jac_x_xdot_u[stage].set_param_sparse(capsule->impl_dae_fun_jac_x_xdot_u+stage, n_update, idx, p); - {% elif solver_options.integrator_type == "ERK" %} - capsule->forw_vde_casadi[stage].set_param_sparse(capsule->forw_vde_casadi+stage, n_update, idx, p); - capsule->expl_ode_fun[stage].set_param_sparse(capsule->expl_ode_fun+stage, n_update, idx, p); - - {%- if solver_options.hessian_approx == "EXACT" %} - capsule->hess_vde_casadi[stage].set_param_sparse(capsule->hess_vde_casadi+stage, n_update, idx, p); - {%- endif %} - {% elif solver_options.integrator_type == "GNSF" %} - {% if model.gnsf.purely_linear != 1 %} - capsule->gnsf_phi_fun[stage].set_param_sparse(capsule->gnsf_phi_fun+stage, n_update, idx, p); - capsule->gnsf_phi_fun_jac_y[stage].set_param_sparse(capsule->gnsf_phi_fun_jac_y+stage, n_update, idx, p); - capsule->gnsf_phi_jac_y_uhat[stage].set_param_sparse(capsule->gnsf_phi_jac_y_uhat+stage, n_update, idx, p); - {% if model.gnsf.nontrivial_f_LO == 1 %} - capsule->gnsf_f_lo_jac_x1_x1dot_u_z[stage].set_param_sparse(capsule->gnsf_f_lo_jac_x1_x1dot_u_z+stage, n_update, idx, p); - {%- endif %} - {%- endif %} - {% elif solver_options.integrator_type == "DISCRETE" %} - capsule->discr_dyn_phi_fun[stage].set_param_sparse(capsule->discr_dyn_phi_fun+stage, n_update, idx, p); - capsule->discr_dyn_phi_fun_jac_ut_xt[stage].set_param_sparse(capsule->discr_dyn_phi_fun_jac_ut_xt+stage, n_update, idx, p); - {%- if solver_options.hessian_approx == "EXACT" %} - capsule->discr_dyn_phi_fun_jac_ut_xt_hess[stage].set_param_sparse(capsule->discr_dyn_phi_fun_jac_ut_xt_hess+stage, n_update, idx, p); - {% endif %} - {%- endif %}{# integrator_type #} - - // constraints - {% if constraints.constr_type == "BGP" %} - capsule->phi_constraint[stage].set_param_sparse(capsule->phi_constraint+stage, n_update, idx, p); - {% elif constraints.constr_type == "BGH" and dims.nh > 0 %} - capsule->nl_constr_h_fun_jac[stage].set_param_sparse(capsule->nl_constr_h_fun_jac+stage, n_update, idx, p); - capsule->nl_constr_h_fun[stage].set_param_sparse(capsule->nl_constr_h_fun+stage, n_update, idx, p); - {%- if solver_options.hessian_approx == "EXACT" %} - capsule->nl_constr_h_fun_jac_hess[stage].set_param_sparse(capsule->nl_constr_h_fun_jac_hess+stage, n_update, idx, p); - {%- endif %} - {%- endif %} - - // cost - if (stage == 0) - { - {%- if cost.cost_type_0 == "NONLINEAR_LS" %} - capsule->cost_y_0_fun.set_param_sparse(&capsule->cost_y_0_fun, n_update, idx, p); - capsule->cost_y_0_fun_jac_ut_xt.set_param_sparse(&capsule->cost_y_0_fun_jac_ut_xt, n_update, idx, p); - capsule->cost_y_0_hess.set_param_sparse(&capsule->cost_y_0_hess, n_update, idx, p); - {%- elif cost.cost_type_0 == "CONVEX_OVER_NONLINEAR" %} - capsule->conl_cost_0_fun.set_param_sparse(&capsule->conl_cost_0_fun, n_update, idx, p); - capsule->conl_cost_0_fun_jac_hess.set_param_sparse(&capsule->conl_cost_0_fun_jac_hess, n_update, idx, p); - {%- elif cost.cost_type_0 == "EXTERNAL" %} - capsule->ext_cost_0_fun.set_param_sparse(&capsule->ext_cost_0_fun, n_update, idx, p); - capsule->ext_cost_0_fun_jac.set_param_sparse(&capsule->ext_cost_0_fun_jac, n_update, idx, p); - capsule->ext_cost_0_fun_jac_hess.set_param_sparse(&capsule->ext_cost_0_fun_jac_hess, n_update, idx, p); - {% endif %} - } - else // 0 < stage < N - { - {%- if cost.cost_type == "NONLINEAR_LS" %} - capsule->cost_y_fun[stage-1].set_param_sparse(capsule->cost_y_fun+stage-1, n_update, idx, p); - capsule->cost_y_fun_jac_ut_xt[stage-1].set_param_sparse(capsule->cost_y_fun_jac_ut_xt+stage-1, n_update, idx, p); - capsule->cost_y_hess[stage-1].set_param_sparse(capsule->cost_y_hess+stage-1, n_update, idx, p); - {%- elif cost.cost_type == "CONVEX_OVER_NONLINEAR" %} - capsule->conl_cost_fun[stage-1].set_param_sparse(capsule->conl_cost_fun+stage-1, n_update, idx, p); - capsule->conl_cost_fun_jac_hess[stage-1].set_param_sparse(capsule->conl_cost_fun_jac_hess+stage-1, n_update, idx, p); - {%- elif cost.cost_type == "EXTERNAL" %} - capsule->ext_cost_fun[stage-1].set_param_sparse(capsule->ext_cost_fun+stage-1, n_update, idx, p); - capsule->ext_cost_fun_jac[stage-1].set_param_sparse(capsule->ext_cost_fun_jac+stage-1, n_update, idx, p); - capsule->ext_cost_fun_jac_hess[stage-1].set_param_sparse(capsule->ext_cost_fun_jac_hess+stage-1, n_update, idx, p); - {%- endif %} - } - } - - else // stage == N - { - // terminal shooting node has no dynamics - // cost - {%- if cost.cost_type_e == "NONLINEAR_LS" %} - capsule->cost_y_e_fun.set_param_sparse(&capsule->cost_y_e_fun, n_update, idx, p); - capsule->cost_y_e_fun_jac_ut_xt.set_param_sparse(&capsule->cost_y_e_fun_jac_ut_xt, n_update, idx, p); - capsule->cost_y_e_hess.set_param_sparse(&capsule->cost_y_e_hess, n_update, idx, p); - {%- elif cost.cost_type_e == "CONVEX_OVER_NONLINEAR" %} - capsule->conl_cost_e_fun.set_param_sparse(&capsule->conl_cost_e_fun, n_update, idx, p); - capsule->conl_cost_e_fun_jac_hess.set_param_sparse(&capsule->conl_cost_e_fun_jac_hess, n_update, idx, p); - {%- elif cost.cost_type_e == "EXTERNAL" %} - capsule->ext_cost_e_fun.set_param_sparse(&capsule->ext_cost_e_fun, n_update, idx, p); - capsule->ext_cost_e_fun_jac.set_param_sparse(&capsule->ext_cost_e_fun_jac, n_update, idx, p); - capsule->ext_cost_e_fun_jac_hess.set_param_sparse(&capsule->ext_cost_e_fun_jac_hess, n_update, idx, p); - {% endif %} - // constraints - {% if constraints.constr_type_e == "BGP" %} - capsule->phi_e_constraint.set_param_sparse(&capsule->phi_e_constraint, n_update, idx, p); - {% elif constraints.constr_type_e == "BGH" and dims.nh_e > 0 %} - capsule->nl_constr_h_e_fun_jac.set_param_sparse(&capsule->nl_constr_h_e_fun_jac, n_update, idx, p); - capsule->nl_constr_h_e_fun.set_param_sparse(&capsule->nl_constr_h_e_fun, n_update, idx, p); - {%- if solver_options.hessian_approx == "EXACT" %} - capsule->nl_constr_h_e_fun_jac_hess.set_param_sparse(&capsule->nl_constr_h_e_fun_jac_hess, n_update, idx, p); - {%- endif %} - {% endif %} - } -{% endif %}{# if dims.np #} - - return solver_status; -} - -int {{ model.name }}_acados_solve({{ model.name }}_solver_capsule* capsule) -{ - // solve NLP - int solver_status = ocp_nlp_solve(capsule->nlp_solver, capsule->nlp_in, capsule->nlp_out); - - return solver_status; -} - - -int {{ model.name }}_acados_free({{ model.name }}_solver_capsule* capsule) -{ - // before destroying, keep some info - const int N = capsule->nlp_solver_plan->N; - {%- if custom_update_filename != "" %} - custom_update_terminate_function(capsule); - {%- endif %} - // free memory - ocp_nlp_solver_opts_destroy(capsule->nlp_opts); - ocp_nlp_in_destroy(capsule->nlp_in); - ocp_nlp_out_destroy(capsule->nlp_out); - ocp_nlp_out_destroy(capsule->sens_out); - ocp_nlp_solver_destroy(capsule->nlp_solver); - ocp_nlp_dims_destroy(capsule->nlp_dims); - ocp_nlp_config_destroy(capsule->nlp_config); - ocp_nlp_plan_destroy(capsule->nlp_solver_plan); - - /* free external function */ - // dynamics -{%- if solver_options.integrator_type == "IRK" %} - for (int i = 0; i < N; i++) - { - external_function_param_{{ model.dyn_ext_fun_type }}_free(&capsule->impl_dae_fun[i]); - external_function_param_{{ model.dyn_ext_fun_type }}_free(&capsule->impl_dae_fun_jac_x_xdot_z[i]); - external_function_param_{{ model.dyn_ext_fun_type }}_free(&capsule->impl_dae_jac_x_xdot_u_z[i]); - {%- if solver_options.hessian_approx == "EXACT" %} - external_function_param_{{ model.dyn_ext_fun_type }}_free(&capsule->impl_dae_hess[i]); - {%- endif %} - } - free(capsule->impl_dae_fun); - free(capsule->impl_dae_fun_jac_x_xdot_z); - free(capsule->impl_dae_jac_x_xdot_u_z); - {%- if solver_options.hessian_approx == "EXACT" %} - free(capsule->impl_dae_hess); - {%- endif %} - -{%- elif solver_options.integrator_type == "LIFTED_IRK" %} - for (int i = 0; i < N; i++) - { - external_function_param_{{ model.dyn_ext_fun_type }}_free(&capsule->impl_dae_fun[i]); - external_function_param_{{ model.dyn_ext_fun_type }}_free(&capsule->impl_dae_fun_jac_x_xdot_u[i]); - } - free(capsule->impl_dae_fun); - free(capsule->impl_dae_fun_jac_x_xdot_u); - -{%- elif solver_options.integrator_type == "ERK" %} - for (int i = 0; i < N; i++) - { - external_function_param_casadi_free(&capsule->forw_vde_casadi[i]); - external_function_param_casadi_free(&capsule->expl_ode_fun[i]); - {%- if solver_options.hessian_approx == "EXACT" %} - external_function_param_casadi_free(&capsule->hess_vde_casadi[i]); - {%- endif %} - } - free(capsule->forw_vde_casadi); - free(capsule->expl_ode_fun); - {%- if solver_options.hessian_approx == "EXACT" %} - free(capsule->hess_vde_casadi); - {%- endif %} - -{%- elif solver_options.integrator_type == "GNSF" %} - for (int i = 0; i < N; i++) - { - {% if model.gnsf.purely_linear != 1 %} - external_function_param_casadi_free(&capsule->gnsf_phi_fun[i]); - external_function_param_casadi_free(&capsule->gnsf_phi_fun_jac_y[i]); - external_function_param_casadi_free(&capsule->gnsf_phi_jac_y_uhat[i]); - {% if model.gnsf.nontrivial_f_LO == 1 %} - external_function_param_casadi_free(&capsule->gnsf_f_lo_jac_x1_x1dot_u_z[i]); - {%- endif %} - {%- endif %} - external_function_param_casadi_free(&capsule->gnsf_get_matrices_fun[i]); - } - {% if model.gnsf.purely_linear != 1 %} - free(capsule->gnsf_phi_fun); - free(capsule->gnsf_phi_fun_jac_y); - free(capsule->gnsf_phi_jac_y_uhat); - {% if model.gnsf.nontrivial_f_LO == 1 %} - free(capsule->gnsf_f_lo_jac_x1_x1dot_u_z); - {%- endif %} - {%- endif %} - free(capsule->gnsf_get_matrices_fun); -{%- elif solver_options.integrator_type == "DISCRETE" %} - for (int i = 0; i < N; i++) - { - external_function_param_{{ model.dyn_ext_fun_type }}_free(&capsule->discr_dyn_phi_fun[i]); - external_function_param_{{ model.dyn_ext_fun_type }}_free(&capsule->discr_dyn_phi_fun_jac_ut_xt[i]); - {%- if solver_options.hessian_approx == "EXACT" %} - external_function_param_{{ model.dyn_ext_fun_type }}_free(&capsule->discr_dyn_phi_fun_jac_ut_xt_hess[i]); - {%- endif %} - } - free(capsule->discr_dyn_phi_fun); - free(capsule->discr_dyn_phi_fun_jac_ut_xt); - {%- if solver_options.hessian_approx == "EXACT" %} - free(capsule->discr_dyn_phi_fun_jac_ut_xt_hess); - {%- endif %} - -{%- endif %} - - // cost -{%- if cost.cost_type_0 == "NONLINEAR_LS" %} - external_function_param_casadi_free(&capsule->cost_y_0_fun); - external_function_param_casadi_free(&capsule->cost_y_0_fun_jac_ut_xt); - external_function_param_casadi_free(&capsule->cost_y_0_hess); -{%- elif cost.cost_type_0 == "CONVEX_OVER_NONLINEAR" %} - external_function_param_casadi_free(&capsule->conl_cost_0_fun); - external_function_param_casadi_free(&capsule->conl_cost_0_fun_jac_hess); -{%- elif cost.cost_type_0 == "EXTERNAL" %} - external_function_param_{{ cost.cost_ext_fun_type_0 }}_free(&capsule->ext_cost_0_fun); - external_function_param_{{ cost.cost_ext_fun_type_0 }}_free(&capsule->ext_cost_0_fun_jac); - external_function_param_{{ cost.cost_ext_fun_type_0 }}_free(&capsule->ext_cost_0_fun_jac_hess); -{%- endif %} -{%- if cost.cost_type == "NONLINEAR_LS" %} - for (int i = 0; i < N - 1; i++) - { - external_function_param_casadi_free(&capsule->cost_y_fun[i]); - external_function_param_casadi_free(&capsule->cost_y_fun_jac_ut_xt[i]); - external_function_param_casadi_free(&capsule->cost_y_hess[i]); - } - free(capsule->cost_y_fun); - free(capsule->cost_y_fun_jac_ut_xt); - free(capsule->cost_y_hess); -{%- elif cost.cost_type == "CONVEX_OVER_NONLINEAR" %} - for (int i = 0; i < N - 1; i++) - { - external_function_param_casadi_free(&capsule->conl_cost_fun[i]); - external_function_param_casadi_free(&capsule->conl_cost_fun_jac_hess[i]); - } - free(capsule->conl_cost_fun); - free(capsule->conl_cost_fun_jac_hess); -{%- elif cost.cost_type == "EXTERNAL" %} - for (int i = 0; i < N - 1; i++) - { - external_function_param_{{ cost.cost_ext_fun_type }}_free(&capsule->ext_cost_fun[i]); - external_function_param_{{ cost.cost_ext_fun_type }}_free(&capsule->ext_cost_fun_jac[i]); - external_function_param_{{ cost.cost_ext_fun_type }}_free(&capsule->ext_cost_fun_jac_hess[i]); - } - free(capsule->ext_cost_fun); - free(capsule->ext_cost_fun_jac); - free(capsule->ext_cost_fun_jac_hess); -{%- endif %} -{%- if cost.cost_type_e == "NONLINEAR_LS" %} - external_function_param_casadi_free(&capsule->cost_y_e_fun); - external_function_param_casadi_free(&capsule->cost_y_e_fun_jac_ut_xt); - external_function_param_casadi_free(&capsule->cost_y_e_hess); -{%- elif cost.cost_type_e == "CONVEX_OVER_NONLINEAR" %} - external_function_param_casadi_free(&capsule->conl_cost_e_fun); - external_function_param_casadi_free(&capsule->conl_cost_e_fun_jac_hess); -{%- elif cost.cost_type_e == "EXTERNAL" %} - external_function_param_{{ cost.cost_ext_fun_type_e }}_free(&capsule->ext_cost_e_fun); - external_function_param_{{ cost.cost_ext_fun_type_e }}_free(&capsule->ext_cost_e_fun_jac); - external_function_param_{{ cost.cost_ext_fun_type_e }}_free(&capsule->ext_cost_e_fun_jac_hess); -{%- endif %} - - // constraints -{%- if constraints.constr_type == "BGH" and dims.nh > 0 %} - for (int i = 0; i < N; i++) - { - external_function_param_casadi_free(&capsule->nl_constr_h_fun_jac[i]); - external_function_param_casadi_free(&capsule->nl_constr_h_fun[i]); - } - {%- if solver_options.hessian_approx == "EXACT" %} - for (int i = 0; i < N; i++) - { - external_function_param_casadi_free(&capsule->nl_constr_h_fun_jac_hess[i]); - } - {%- endif %} - free(capsule->nl_constr_h_fun_jac); - free(capsule->nl_constr_h_fun); - {%- if solver_options.hessian_approx == "EXACT" %} - free(capsule->nl_constr_h_fun_jac_hess); - {%- endif %} - -{%- elif constraints.constr_type == "BGP" and dims.nphi > 0 %} - for (int i = 0; i < N; i++) - { - external_function_param_casadi_free(&capsule->phi_constraint[i]); - } - free(capsule->phi_constraint); -{%- endif %} - -{%- if constraints.constr_type_e == "BGH" and dims.nh_e > 0 %} - external_function_param_casadi_free(&capsule->nl_constr_h_e_fun_jac); - external_function_param_casadi_free(&capsule->nl_constr_h_e_fun); -{%- if solver_options.hessian_approx == "EXACT" %} - external_function_param_casadi_free(&capsule->nl_constr_h_e_fun_jac_hess); -{%- endif %} -{%- elif constraints.constr_type_e == "BGP" and dims.nphi_e > 0 %} - external_function_param_casadi_free(&capsule->phi_e_constraint); -{%- endif %} - - return 0; -} - - -void {{ model.name }}_acados_print_stats({{ model.name }}_solver_capsule* capsule) -{ - int sqp_iter, stat_m, stat_n, tmp_int; - ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "sqp_iter", &sqp_iter); - ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "stat_n", &stat_n); - ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "stat_m", &stat_m); - - {% set stat_n_max = 12 %} - double stat[{{ solver_options.nlp_solver_max_iter * stat_n_max }}]; - ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "statistics", stat); - - int nrow = sqp_iter+1 < stat_m ? sqp_iter+1 : stat_m; - - printf("iter\tres_stat\tres_eq\t\tres_ineq\tres_comp\tqp_stat\tqp_iter\talpha"); - if (stat_n > 8) - printf("\t\tqp_res_stat\tqp_res_eq\tqp_res_ineq\tqp_res_comp"); - printf("\n"); - -{%- if solver_options.nlp_solver_type == "SQP" %} - - for (int i = 0; i < nrow; i++) - { - for (int j = 0; j < stat_n + 1; j++) - { - if (j == 0 || j == 5 || j == 6) - { - tmp_int = (int) stat[i + j * nrow]; - printf("%d\t", tmp_int); - } - else - { - printf("%e\t", stat[i + j * nrow]); - } - } - printf("\n"); - } -{% else %} - printf("iter\tqp_stat\tqp_iter\n"); - for (int i = 0; i < nrow; i++) - { - for (int j = 0; j < stat_n + 1; j++) - { - tmp_int = (int) stat[i + j * nrow]; - printf("%d\t", tmp_int); - } - printf("\n"); - } -{%- endif %} -} - -int {{ model.name }}_acados_custom_update({{ model.name }}_solver_capsule* capsule, double* data, int data_len) -{ -{%- if custom_update_filename == "" %} - (void)capsule; - (void)data; - (void)data_len; - printf("\ndummy function that can be called in between solver calls to update parameters or numerical data efficiently in C.\n"); - printf("nothing set yet..\n"); - return 1; -{% else %} - custom_update_function(capsule, data, data_len); -{%- endif %} -} - - - -ocp_nlp_in *{{ model.name }}_acados_get_nlp_in({{ model.name }}_solver_capsule* capsule) { return capsule->nlp_in; } -ocp_nlp_out *{{ model.name }}_acados_get_nlp_out({{ model.name }}_solver_capsule* capsule) { return capsule->nlp_out; } -ocp_nlp_out *{{ model.name }}_acados_get_sens_out({{ model.name }}_solver_capsule* capsule) { return capsule->sens_out; } -ocp_nlp_solver *{{ model.name }}_acados_get_nlp_solver({{ model.name }}_solver_capsule* capsule) { return capsule->nlp_solver; } -ocp_nlp_config *{{ model.name }}_acados_get_nlp_config({{ model.name }}_solver_capsule* capsule) { return capsule->nlp_config; } -void *{{ model.name }}_acados_get_nlp_opts({{ model.name }}_solver_capsule* capsule) { return capsule->nlp_opts; } -ocp_nlp_dims *{{ model.name }}_acados_get_nlp_dims({{ model.name }}_solver_capsule* capsule) { return capsule->nlp_dims; } -ocp_nlp_plan_t *{{ model.name }}_acados_get_nlp_plan({{ model.name }}_solver_capsule* capsule) { return capsule->nlp_solver_plan; } diff --git a/third_party/acados/acados_template/c_templates_tera/acados_solver.in.h b/third_party/acados/acados_template/c_templates_tera/acados_solver.in.h deleted file mode 100644 index 5cf38aa8c8..0000000000 --- a/third_party/acados/acados_template/c_templates_tera/acados_solver.in.h +++ /dev/null @@ -1,241 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - -#ifndef ACADOS_SOLVER_{{ model.name }}_H_ -#define ACADOS_SOLVER_{{ model.name }}_H_ - -#include "acados/utils/types.h" - -#include "acados_c/ocp_nlp_interface.h" -#include "acados_c/external_function_interface.h" - -#define {{ model.name | upper }}_NX {{ dims.nx }} -#define {{ model.name | upper }}_NZ {{ dims.nz }} -#define {{ model.name | upper }}_NU {{ dims.nu }} -#define {{ model.name | upper }}_NP {{ dims.np }} -#define {{ model.name | upper }}_NBX {{ dims.nbx }} -#define {{ model.name | upper }}_NBX0 {{ dims.nbx_0 }} -#define {{ model.name | upper }}_NBU {{ dims.nbu }} -#define {{ model.name | upper }}_NSBX {{ dims.nsbx }} -#define {{ model.name | upper }}_NSBU {{ dims.nsbu }} -#define {{ model.name | upper }}_NSH {{ dims.nsh }} -#define {{ model.name | upper }}_NSG {{ dims.nsg }} -#define {{ model.name | upper }}_NSPHI {{ dims.nsphi }} -#define {{ model.name | upper }}_NSHN {{ dims.nsh_e }} -#define {{ model.name | upper }}_NSGN {{ dims.nsg_e }} -#define {{ model.name | upper }}_NSPHIN {{ dims.nsphi_e }} -#define {{ model.name | upper }}_NSBXN {{ dims.nsbx_e }} -#define {{ model.name | upper }}_NS {{ dims.ns }} -#define {{ model.name | upper }}_NSN {{ dims.ns_e }} -#define {{ model.name | upper }}_NG {{ dims.ng }} -#define {{ model.name | upper }}_NBXN {{ dims.nbx_e }} -#define {{ model.name | upper }}_NGN {{ dims.ng_e }} -#define {{ model.name | upper }}_NY0 {{ dims.ny_0 }} -#define {{ model.name | upper }}_NY {{ dims.ny }} -#define {{ model.name | upper }}_NYN {{ dims.ny_e }} -#define {{ model.name | upper }}_N {{ dims.N }} -#define {{ model.name | upper }}_NH {{ dims.nh }} -#define {{ model.name | upper }}_NPHI {{ dims.nphi }} -#define {{ model.name | upper }}_NHN {{ dims.nh_e }} -#define {{ model.name | upper }}_NPHIN {{ dims.nphi_e }} -#define {{ model.name | upper }}_NR {{ dims.nr }} - -#ifdef __cplusplus -extern "C" { -#endif - -{%- if not solver_options.custom_update_filename %} - {%- set custom_update_filename = "" %} -{% else %} - {%- set custom_update_filename = solver_options.custom_update_filename %} -{%- endif %} - -// ** capsule for solver data ** -typedef struct {{ model.name }}_solver_capsule -{ - // acados objects - ocp_nlp_in *nlp_in; - ocp_nlp_out *nlp_out; - ocp_nlp_out *sens_out; - ocp_nlp_solver *nlp_solver; - void *nlp_opts; - ocp_nlp_plan_t *nlp_solver_plan; - ocp_nlp_config *nlp_config; - ocp_nlp_dims *nlp_dims; - - // number of expected runtime parameters - unsigned int nlp_np; - - /* external functions */ - // dynamics -{% if solver_options.integrator_type == "ERK" %} - external_function_param_casadi *forw_vde_casadi; - external_function_param_casadi *expl_ode_fun; -{% if solver_options.hessian_approx == "EXACT" %} - external_function_param_casadi *hess_vde_casadi; -{%- endif %} -{% elif solver_options.integrator_type == "IRK" %} - external_function_param_{{ model.dyn_ext_fun_type }} *impl_dae_fun; - external_function_param_{{ model.dyn_ext_fun_type }} *impl_dae_fun_jac_x_xdot_z; - external_function_param_{{ model.dyn_ext_fun_type }} *impl_dae_jac_x_xdot_u_z; -{% if solver_options.hessian_approx == "EXACT" %} - external_function_param_{{ model.dyn_ext_fun_type }} *impl_dae_hess; -{%- endif %} -{% elif solver_options.integrator_type == "LIFTED_IRK" %} - external_function_param_{{ model.dyn_ext_fun_type }} *impl_dae_fun; - external_function_param_{{ model.dyn_ext_fun_type }} *impl_dae_fun_jac_x_xdot_u; -{% elif solver_options.integrator_type == "GNSF" %} - external_function_param_casadi *gnsf_phi_fun; - external_function_param_casadi *gnsf_phi_fun_jac_y; - external_function_param_casadi *gnsf_phi_jac_y_uhat; - external_function_param_casadi *gnsf_f_lo_jac_x1_x1dot_u_z; - external_function_param_casadi *gnsf_get_matrices_fun; -{% elif solver_options.integrator_type == "DISCRETE" %} - external_function_param_{{ model.dyn_ext_fun_type }} *discr_dyn_phi_fun; - external_function_param_{{ model.dyn_ext_fun_type }} *discr_dyn_phi_fun_jac_ut_xt; -{%- if solver_options.hessian_approx == "EXACT" %} - external_function_param_{{ model.dyn_ext_fun_type }} *discr_dyn_phi_fun_jac_ut_xt_hess; -{%- endif %} -{%- endif %} - - - // cost -{% if cost.cost_type == "NONLINEAR_LS" %} - external_function_param_casadi *cost_y_fun; - external_function_param_casadi *cost_y_fun_jac_ut_xt; - external_function_param_casadi *cost_y_hess; -{% elif cost.cost_type == "CONVEX_OVER_NONLINEAR" %} - external_function_param_casadi *conl_cost_fun; - external_function_param_casadi *conl_cost_fun_jac_hess; -{%- elif cost.cost_type == "EXTERNAL" %} - external_function_param_{{ cost.cost_ext_fun_type }} *ext_cost_fun; - external_function_param_{{ cost.cost_ext_fun_type }} *ext_cost_fun_jac; - external_function_param_{{ cost.cost_ext_fun_type }} *ext_cost_fun_jac_hess; -{% endif %} - -{% if cost.cost_type_0 == "NONLINEAR_LS" %} - external_function_param_casadi cost_y_0_fun; - external_function_param_casadi cost_y_0_fun_jac_ut_xt; - external_function_param_casadi cost_y_0_hess; -{% elif cost.cost_type_0 == "CONVEX_OVER_NONLINEAR" %} - external_function_param_casadi conl_cost_0_fun; - external_function_param_casadi conl_cost_0_fun_jac_hess; -{% elif cost.cost_type_0 == "EXTERNAL" %} - external_function_param_{{ cost.cost_ext_fun_type_0 }} ext_cost_0_fun; - external_function_param_{{ cost.cost_ext_fun_type_0 }} ext_cost_0_fun_jac; - external_function_param_{{ cost.cost_ext_fun_type_0 }} ext_cost_0_fun_jac_hess; -{%- endif %} - -{% if cost.cost_type_e == "NONLINEAR_LS" %} - external_function_param_casadi cost_y_e_fun; - external_function_param_casadi cost_y_e_fun_jac_ut_xt; - external_function_param_casadi cost_y_e_hess; -{% elif cost.cost_type_e == "CONVEX_OVER_NONLINEAR" %} - external_function_param_casadi conl_cost_e_fun; - external_function_param_casadi conl_cost_e_fun_jac_hess; -{% elif cost.cost_type_e == "EXTERNAL" %} - external_function_param_{{ cost.cost_ext_fun_type_e }} ext_cost_e_fun; - external_function_param_{{ cost.cost_ext_fun_type_e }} ext_cost_e_fun_jac; - external_function_param_{{ cost.cost_ext_fun_type_e }} ext_cost_e_fun_jac_hess; -{%- endif %} - - // constraints -{%- if constraints.constr_type == "BGP" %} - external_function_param_casadi *phi_constraint; -{% elif constraints.constr_type == "BGH" and dims.nh > 0 %} - external_function_param_casadi *nl_constr_h_fun_jac; - external_function_param_casadi *nl_constr_h_fun; -{%- if solver_options.hessian_approx == "EXACT" %} - external_function_param_casadi *nl_constr_h_fun_jac_hess; -{%- endif %} -{%- endif %} - - -{% if constraints.constr_type_e == "BGP" %} - external_function_param_casadi phi_e_constraint; -{% elif constraints.constr_type_e == "BGH" and dims.nh_e > 0 %} - external_function_param_casadi nl_constr_h_e_fun_jac; - external_function_param_casadi nl_constr_h_e_fun; -{%- if solver_options.hessian_approx == "EXACT" %} - external_function_param_casadi nl_constr_h_e_fun_jac_hess; -{%- endif %} -{%- endif %} - -{%- if custom_update_filename != "" %} - void * custom_update_memory; -{%- endif %} - -} {{ model.name }}_solver_capsule; - -ACADOS_SYMBOL_EXPORT {{ model.name }}_solver_capsule * {{ model.name }}_acados_create_capsule(void); -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_free_capsule({{ model.name }}_solver_capsule *capsule); - -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_create({{ model.name }}_solver_capsule * capsule); - -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_reset({{ model.name }}_solver_capsule* capsule, int reset_qp_solver_mem); - -/** - * Generic version of {{ model.name }}_acados_create which allows to use a different number of shooting intervals than - * the number used for code generation. If new_time_steps=NULL and n_time_steps matches the number used for code - * generation, the time-steps from code generation is used. - */ -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_create_with_discretization({{ model.name }}_solver_capsule * capsule, int n_time_steps, double* new_time_steps); -/** - * Update the time step vector. Number N must be identical to the currently set number of shooting nodes in the - * nlp_solver_plan. Returns 0 if no error occurred and a otherwise a value other than 0. - */ -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_update_time_steps({{ model.name }}_solver_capsule * capsule, int N, double* new_time_steps); -/** - * This function is used for updating an already initialized solver with a different number of qp_cond_N. - */ -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_update_qp_solver_cond_N({{ model.name }}_solver_capsule * capsule, int qp_solver_cond_N); -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_update_params({{ model.name }}_solver_capsule * capsule, int stage, double *value, int np); -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_update_params_sparse({{ model.name }}_solver_capsule * capsule, int stage, int *idx, double *p, int n_update); - -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_solve({{ model.name }}_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_free({{ model.name }}_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT void {{ model.name }}_acados_print_stats({{ model.name }}_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_custom_update({{ model.name }}_solver_capsule* capsule, double* data, int data_len); - - -ACADOS_SYMBOL_EXPORT ocp_nlp_in *{{ model.name }}_acados_get_nlp_in({{ model.name }}_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT ocp_nlp_out *{{ model.name }}_acados_get_nlp_out({{ model.name }}_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT ocp_nlp_out *{{ model.name }}_acados_get_sens_out({{ model.name }}_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT ocp_nlp_solver *{{ model.name }}_acados_get_nlp_solver({{ model.name }}_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT ocp_nlp_config *{{ model.name }}_acados_get_nlp_config({{ model.name }}_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT void *{{ model.name }}_acados_get_nlp_opts({{ model.name }}_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT ocp_nlp_dims *{{ model.name }}_acados_get_nlp_dims({{ model.name }}_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT ocp_nlp_plan_t *{{ model.name }}_acados_get_nlp_plan({{ model.name }}_solver_capsule * capsule); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_SOLVER_{{ model.name }}_H_ diff --git a/third_party/acados/acados_template/c_templates_tera/acados_solver.in.pxd b/third_party/acados/acados_template/c_templates_tera/acados_solver.in.pxd deleted file mode 100644 index 233e3f79da..0000000000 --- a/third_party/acados/acados_template/c_templates_tera/acados_solver.in.pxd +++ /dev/null @@ -1,62 +0,0 @@ -# -# Copyright (c) The acados authors. -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# - -cimport acados_solver_common - -cdef extern from "acados_solver_{{ model.name }}.h": - ctypedef struct nlp_solver_capsule "{{ model.name }}_solver_capsule": - pass - - nlp_solver_capsule * acados_create_capsule "{{ model.name }}_acados_create_capsule"() - int acados_free_capsule "{{ model.name }}_acados_free_capsule"(nlp_solver_capsule *capsule) - - int acados_create "{{ model.name }}_acados_create"(nlp_solver_capsule * capsule) - - int acados_create_with_discretization "{{ model.name }}_acados_create_with_discretization"(nlp_solver_capsule * capsule, int n_time_steps, double* new_time_steps) - int acados_update_time_steps "{{ model.name }}_acados_update_time_steps"(nlp_solver_capsule * capsule, int N, double* new_time_steps) - int acados_update_qp_solver_cond_N "{{ model.name }}_acados_update_qp_solver_cond_N"(nlp_solver_capsule * capsule, int qp_solver_cond_N) - - int acados_update_params "{{ model.name }}_acados_update_params"(nlp_solver_capsule * capsule, int stage, double *value, int np_) - int acados_update_params_sparse "{{ model.name }}_acados_update_params_sparse"(nlp_solver_capsule * capsule, int stage, int *idx, double *p, int n_update) - int acados_solve "{{ model.name }}_acados_solve"(nlp_solver_capsule * capsule) - int acados_reset "{{ model.name }}_acados_reset"(nlp_solver_capsule * capsule, int reset_qp_solver_mem) - int acados_free "{{ model.name }}_acados_free"(nlp_solver_capsule * capsule) - void acados_print_stats "{{ model.name }}_acados_print_stats"(nlp_solver_capsule * capsule) - - int acados_custom_update "{{ model.name }}_acados_custom_update"(nlp_solver_capsule* capsule, double * data, int data_len) - - acados_solver_common.ocp_nlp_in *acados_get_nlp_in "{{ model.name }}_acados_get_nlp_in"(nlp_solver_capsule * capsule) - acados_solver_common.ocp_nlp_out *acados_get_nlp_out "{{ model.name }}_acados_get_nlp_out"(nlp_solver_capsule * capsule) - acados_solver_common.ocp_nlp_out *acados_get_sens_out "{{ model.name }}_acados_get_sens_out"(nlp_solver_capsule * capsule) - acados_solver_common.ocp_nlp_solver *acados_get_nlp_solver "{{ model.name }}_acados_get_nlp_solver"(nlp_solver_capsule * capsule) - acados_solver_common.ocp_nlp_config *acados_get_nlp_config "{{ model.name }}_acados_get_nlp_config"(nlp_solver_capsule * capsule) - void *acados_get_nlp_opts "{{ model.name }}_acados_get_nlp_opts"(nlp_solver_capsule * capsule) - acados_solver_common.ocp_nlp_dims *acados_get_nlp_dims "{{ model.name }}_acados_get_nlp_dims"(nlp_solver_capsule * capsule) - acados_solver_common.ocp_nlp_plan *acados_get_nlp_plan "{{ model.name }}_acados_get_nlp_plan"(nlp_solver_capsule * capsule) diff --git a/third_party/acados/acados_template/c_templates_tera/constraints.in.h b/third_party/acados/acados_template/c_templates_tera/constraints.in.h deleted file mode 100644 index d71ce5cc22..0000000000 --- a/third_party/acados/acados_template/c_templates_tera/constraints.in.h +++ /dev/null @@ -1,110 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - -#ifndef {{ model.name }}_CONSTRAINTS -#define {{ model.name }}_CONSTRAINTS - -#ifdef __cplusplus -extern "C" { -#endif - -{% if dims.nphi > 0 %} -int {{ model.name }}_phi_constraint(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_phi_constraint_work(int *, int *, int *, int *); -const int *{{ model.name }}_phi_constraint_sparsity_in(int); -const int *{{ model.name }}_phi_constraint_sparsity_out(int); -int {{ model.name }}_phi_constraint_n_in(void); -int {{ model.name }}_phi_constraint_n_out(void); -{% endif %} - -{% if dims.nphi_e > 0 %} -int {{ model.name }}_phi_e_constraint(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_phi_e_constraint_work(int *, int *, int *, int *); -const int *{{ model.name }}_phi_e_constraint_sparsity_in(int); -const int *{{ model.name }}_phi_e_constraint_sparsity_out(int); -int {{ model.name }}_phi_e_constraint_n_in(void); -int {{ model.name }}_phi_e_constraint_n_out(void); -{% endif %} - -{% if dims.nh > 0 %} -int {{ model.name }}_constr_h_fun_jac_uxt_zt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_constr_h_fun_jac_uxt_zt_work(int *, int *, int *, int *); -const int *{{ model.name }}_constr_h_fun_jac_uxt_zt_sparsity_in(int); -const int *{{ model.name }}_constr_h_fun_jac_uxt_zt_sparsity_out(int); -int {{ model.name }}_constr_h_fun_jac_uxt_zt_n_in(void); -int {{ model.name }}_constr_h_fun_jac_uxt_zt_n_out(void); - -int {{ model.name }}_constr_h_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_constr_h_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_constr_h_fun_sparsity_in(int); -const int *{{ model.name }}_constr_h_fun_sparsity_out(int); -int {{ model.name }}_constr_h_fun_n_in(void); -int {{ model.name }}_constr_h_fun_n_out(void); - -{% if solver_options.hessian_approx == "EXACT" -%} -int {{ model.name }}_constr_h_fun_jac_uxt_zt_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_constr_h_fun_jac_uxt_zt_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_constr_h_fun_jac_uxt_zt_hess_sparsity_in(int); -const int *{{ model.name }}_constr_h_fun_jac_uxt_zt_hess_sparsity_out(int); -int {{ model.name }}_constr_h_fun_jac_uxt_zt_hess_n_in(void); -int {{ model.name }}_constr_h_fun_jac_uxt_zt_hess_n_out(void); -{% endif %} -{% endif %} - -{% if dims.nh_e > 0 %} -int {{ model.name }}_constr_h_e_fun_jac_uxt_zt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_constr_h_e_fun_jac_uxt_zt_work(int *, int *, int *, int *); -const int *{{ model.name }}_constr_h_e_fun_jac_uxt_zt_sparsity_in(int); -const int *{{ model.name }}_constr_h_e_fun_jac_uxt_zt_sparsity_out(int); -int {{ model.name }}_constr_h_e_fun_jac_uxt_zt_n_in(void); -int {{ model.name }}_constr_h_e_fun_jac_uxt_zt_n_out(void); - -int {{ model.name }}_constr_h_e_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_constr_h_e_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_constr_h_e_fun_sparsity_in(int); -const int *{{ model.name }}_constr_h_e_fun_sparsity_out(int); -int {{ model.name }}_constr_h_e_fun_n_in(void); -int {{ model.name }}_constr_h_e_fun_n_out(void); - -{% if solver_options.hessian_approx == "EXACT" -%} -int {{ model.name }}_constr_h_e_fun_jac_uxt_zt_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_constr_h_e_fun_jac_uxt_zt_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_constr_h_e_fun_jac_uxt_zt_hess_sparsity_in(int); -const int *{{ model.name }}_constr_h_e_fun_jac_uxt_zt_hess_sparsity_out(int); -int {{ model.name }}_constr_h_e_fun_jac_uxt_zt_hess_n_in(void); -int {{ model.name }}_constr_h_e_fun_jac_uxt_zt_hess_n_out(void); -{% endif %} -{% endif %} - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // {{ model.name }}_CONSTRAINTS diff --git a/third_party/acados/acados_template/c_templates_tera/cost.in.h b/third_party/acados/acados_template/c_templates_tera/cost.in.h deleted file mode 100644 index 45eb09c12e..0000000000 --- a/third_party/acados/acados_template/c_templates_tera/cost.in.h +++ /dev/null @@ -1,238 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef {{ model.name }}_COST -#define {{ model.name }}_COST - -#ifdef __cplusplus -extern "C" { -#endif - - -// Cost at initial shooting node -{% if cost.cost_type_0 == "NONLINEAR_LS" %} -int {{ model.name }}_cost_y_0_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_y_0_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_y_0_fun_sparsity_in(int); -const int *{{ model.name }}_cost_y_0_fun_sparsity_out(int); -int {{ model.name }}_cost_y_0_fun_n_in(void); -int {{ model.name }}_cost_y_0_fun_n_out(void); - -int {{ model.name }}_cost_y_0_fun_jac_ut_xt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_y_0_fun_jac_ut_xt_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_y_0_fun_jac_ut_xt_sparsity_in(int); -const int *{{ model.name }}_cost_y_0_fun_jac_ut_xt_sparsity_out(int); -int {{ model.name }}_cost_y_0_fun_jac_ut_xt_n_in(void); -int {{ model.name }}_cost_y_0_fun_jac_ut_xt_n_out(void); - -int {{ model.name }}_cost_y_0_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_y_0_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_y_0_hess_sparsity_in(int); -const int *{{ model.name }}_cost_y_0_hess_sparsity_out(int); -int {{ model.name }}_cost_y_0_hess_n_in(void); -int {{ model.name }}_cost_y_0_hess_n_out(void); -{% elif cost.cost_type_0 == "CONVEX_OVER_NONLINEAR" %} - -int {{ model.name }}_conl_cost_0_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_conl_cost_0_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_conl_cost_0_fun_sparsity_in(int); -const int *{{ model.name }}_conl_cost_0_fun_sparsity_out(int); -int {{ model.name }}_conl_cost_0_fun_n_in(void); -int {{ model.name }}_conl_cost_0_fun_n_out(void); - -int {{ model.name }}_conl_cost_0_fun_jac_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_conl_cost_0_fun_jac_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_conl_cost_0_fun_jac_hess_sparsity_in(int); -const int *{{ model.name }}_conl_cost_0_fun_jac_hess_sparsity_out(int); -int {{ model.name }}_conl_cost_0_fun_jac_hess_n_in(void); -int {{ model.name }}_conl_cost_0_fun_jac_hess_n_out(void); - -{% elif cost.cost_type_0 == "EXTERNAL" %} - {%- if cost.cost_ext_fun_type_0 == "casadi" %} -int {{ model.name }}_cost_ext_cost_0_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_ext_cost_0_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_ext_cost_0_fun_sparsity_in(int); -const int *{{ model.name }}_cost_ext_cost_0_fun_sparsity_out(int); -int {{ model.name }}_cost_ext_cost_0_fun_n_in(void); -int {{ model.name }}_cost_ext_cost_0_fun_n_out(void); - -int {{ model.name }}_cost_ext_cost_0_fun_jac_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_ext_cost_0_fun_jac_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_ext_cost_0_fun_jac_hess_sparsity_in(int); -const int *{{ model.name }}_cost_ext_cost_0_fun_jac_hess_sparsity_out(int); -int {{ model.name }}_cost_ext_cost_0_fun_jac_hess_n_in(void); -int {{ model.name }}_cost_ext_cost_0_fun_jac_hess_n_out(void); - -int {{ model.name }}_cost_ext_cost_0_fun_jac(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_ext_cost_0_fun_jac_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_ext_cost_0_fun_jac_sparsity_in(int); -const int *{{ model.name }}_cost_ext_cost_0_fun_jac_sparsity_out(int); -int {{ model.name }}_cost_ext_cost_0_fun_jac_n_in(void); -int {{ model.name }}_cost_ext_cost_0_fun_jac_n_out(void); - {%- else %} -int {{ cost.cost_function_ext_cost_0 }}(void **, void **, void *); - {%- endif %} -{% endif %} - - -// Cost at path shooting node -{% if cost.cost_type == "NONLINEAR_LS" %} -int {{ model.name }}_cost_y_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_y_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_y_fun_sparsity_in(int); -const int *{{ model.name }}_cost_y_fun_sparsity_out(int); -int {{ model.name }}_cost_y_fun_n_in(void); -int {{ model.name }}_cost_y_fun_n_out(void); - -int {{ model.name }}_cost_y_fun_jac_ut_xt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_y_fun_jac_ut_xt_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_y_fun_jac_ut_xt_sparsity_in(int); -const int *{{ model.name }}_cost_y_fun_jac_ut_xt_sparsity_out(int); -int {{ model.name }}_cost_y_fun_jac_ut_xt_n_in(void); -int {{ model.name }}_cost_y_fun_jac_ut_xt_n_out(void); - -int {{ model.name }}_cost_y_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_y_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_y_hess_sparsity_in(int); -const int *{{ model.name }}_cost_y_hess_sparsity_out(int); -int {{ model.name }}_cost_y_hess_n_in(void); -int {{ model.name }}_cost_y_hess_n_out(void); - -{% elif cost.cost_type == "CONVEX_OVER_NONLINEAR" %} -int {{ model.name }}_conl_cost_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_conl_cost_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_conl_cost_fun_sparsity_in(int); -const int *{{ model.name }}_conl_cost_fun_sparsity_out(int); -int {{ model.name }}_conl_cost_fun_n_in(void); -int {{ model.name }}_conl_cost_fun_n_out(void); - -int {{ model.name }}_conl_cost_fun_jac_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_conl_cost_fun_jac_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_conl_cost_fun_jac_hess_sparsity_in(int); -const int *{{ model.name }}_conl_cost_fun_jac_hess_sparsity_out(int); -int {{ model.name }}_conl_cost_fun_jac_hess_n_in(void); -int {{ model.name }}_conl_cost_fun_jac_hess_n_out(void); -{% elif cost.cost_type == "EXTERNAL" %} - {%- if cost.cost_ext_fun_type == "casadi" %} -int {{ model.name }}_cost_ext_cost_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_ext_cost_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_ext_cost_fun_sparsity_in(int); -const int *{{ model.name }}_cost_ext_cost_fun_sparsity_out(int); -int {{ model.name }}_cost_ext_cost_fun_n_in(void); -int {{ model.name }}_cost_ext_cost_fun_n_out(void); - -int {{ model.name }}_cost_ext_cost_fun_jac_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_ext_cost_fun_jac_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_ext_cost_fun_jac_hess_sparsity_in(int); -const int *{{ model.name }}_cost_ext_cost_fun_jac_hess_sparsity_out(int); -int {{ model.name }}_cost_ext_cost_fun_jac_hess_n_in(void); -int {{ model.name }}_cost_ext_cost_fun_jac_hess_n_out(void); - -int {{ model.name }}_cost_ext_cost_fun_jac(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_ext_cost_fun_jac_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_ext_cost_fun_jac_sparsity_in(int); -const int *{{ model.name }}_cost_ext_cost_fun_jac_sparsity_out(int); -int {{ model.name }}_cost_ext_cost_fun_jac_n_in(void); -int {{ model.name }}_cost_ext_cost_fun_jac_n_out(void); - {%- else %} -int {{ cost.cost_function_ext_cost }}(void **, void **, void *); - {%- endif %} -{% endif %} - -// Cost at terminal shooting node -{% if cost.cost_type_e == "NONLINEAR_LS" %} -int {{ model.name }}_cost_y_e_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_y_e_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_y_e_fun_sparsity_in(int); -const int *{{ model.name }}_cost_y_e_fun_sparsity_out(int); -int {{ model.name }}_cost_y_e_fun_n_in(void); -int {{ model.name }}_cost_y_e_fun_n_out(void); - -int {{ model.name }}_cost_y_e_fun_jac_ut_xt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_y_e_fun_jac_ut_xt_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_y_e_fun_jac_ut_xt_sparsity_in(int); -const int *{{ model.name }}_cost_y_e_fun_jac_ut_xt_sparsity_out(int); -int {{ model.name }}_cost_y_e_fun_jac_ut_xt_n_in(void); -int {{ model.name }}_cost_y_e_fun_jac_ut_xt_n_out(void); - -int {{ model.name }}_cost_y_e_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_y_e_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_y_e_hess_sparsity_in(int); -const int *{{ model.name }}_cost_y_e_hess_sparsity_out(int); -int {{ model.name }}_cost_y_e_hess_n_in(void); -int {{ model.name }}_cost_y_e_hess_n_out(void); -{% elif cost.cost_type_e == "CONVEX_OVER_NONLINEAR" %} -int {{ model.name }}_conl_cost_e_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_conl_cost_e_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_conl_cost_e_fun_sparsity_in(int); -const int *{{ model.name }}_conl_cost_e_fun_sparsity_out(int); -int {{ model.name }}_conl_cost_e_fun_n_in(void); -int {{ model.name }}_conl_cost_e_fun_n_out(void); - -int {{ model.name }}_conl_cost_e_fun_jac_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_conl_cost_e_fun_jac_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_conl_cost_e_fun_jac_hess_sparsity_in(int); -const int *{{ model.name }}_conl_cost_e_fun_jac_hess_sparsity_out(int); -int {{ model.name }}_conl_cost_e_fun_jac_hess_n_in(void); -int {{ model.name }}_conl_cost_e_fun_jac_hess_n_out(void); -{% elif cost.cost_type_e == "EXTERNAL" %} - {%- if cost.cost_ext_fun_type_e == "casadi" %} -int {{ model.name }}_cost_ext_cost_e_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_ext_cost_e_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_ext_cost_e_fun_sparsity_in(int); -const int *{{ model.name }}_cost_ext_cost_e_fun_sparsity_out(int); -int {{ model.name }}_cost_ext_cost_e_fun_n_in(void); -int {{ model.name }}_cost_ext_cost_e_fun_n_out(void); - -int {{ model.name }}_cost_ext_cost_e_fun_jac_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_ext_cost_e_fun_jac_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_ext_cost_e_fun_jac_hess_sparsity_in(int); -const int *{{ model.name }}_cost_ext_cost_e_fun_jac_hess_sparsity_out(int); -int {{ model.name }}_cost_ext_cost_e_fun_jac_hess_n_in(void); -int {{ model.name }}_cost_ext_cost_e_fun_jac_hess_n_out(void); - -int {{ model.name }}_cost_ext_cost_e_fun_jac(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_ext_cost_e_fun_jac_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_ext_cost_e_fun_jac_sparsity_in(int); -const int *{{ model.name }}_cost_ext_cost_e_fun_jac_sparsity_out(int); -int {{ model.name }}_cost_ext_cost_e_fun_jac_n_in(void); -int {{ model.name }}_cost_ext_cost_e_fun_jac_n_out(void); - {%- else %} -int {{ cost.cost_function_ext_cost_e }}(void **, void **, void *); - {%- endif %} -{% endif %} - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // {{ model.name }}_COST diff --git a/third_party/acados/acados_template/c_templates_tera/main.in.c b/third_party/acados/acados_template/c_templates_tera/main.in.c deleted file mode 100644 index 92a8b33eac..0000000000 --- a/third_party/acados/acados_template/c_templates_tera/main.in.c +++ /dev/null @@ -1,226 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - -{%- if not solver_options.custom_update_filename %} - {%- set custom_update_filename = "" %} -{% else %} - {%- set custom_update_filename = solver_options.custom_update_filename %} -{%- endif %} - -// standard -#include -#include -// acados -#include "acados/utils/print.h" -#include "acados/utils/math.h" -#include "acados_c/ocp_nlp_interface.h" -#include "acados_c/external_function_interface.h" -#include "acados_solver_{{ model.name }}.h" - -// blasfeo -#include "blasfeo/include/blasfeo_d_aux_ext_dep.h" - -#define NX {{ model.name | upper }}_NX -#define NZ {{ model.name | upper }}_NZ -#define NU {{ model.name | upper }}_NU -#define NP {{ model.name | upper }}_NP -#define NBX {{ model.name | upper }}_NBX -#define NBX0 {{ model.name | upper }}_NBX0 -#define NBU {{ model.name | upper }}_NBU -#define NSBX {{ model.name | upper }}_NSBX -#define NSBU {{ model.name | upper }}_NSBU -#define NSH {{ model.name | upper }}_NSH -#define NSG {{ model.name | upper }}_NSG -#define NSPHI {{ model.name | upper }}_NSPHI -#define NSHN {{ model.name | upper }}_NSHN -#define NSGN {{ model.name | upper }}_NSGN -#define NSPHIN {{ model.name | upper }}_NSPHIN -#define NSBXN {{ model.name | upper }}_NSBXN -#define NS {{ model.name | upper }}_NS -#define NSN {{ model.name | upper }}_NSN -#define NG {{ model.name | upper }}_NG -#define NBXN {{ model.name | upper }}_NBXN -#define NGN {{ model.name | upper }}_NGN -#define NY0 {{ model.name | upper }}_NY0 -#define NY {{ model.name | upper }}_NY -#define NYN {{ model.name | upper }}_NYN -#define NH {{ model.name | upper }}_NH -#define NPHI {{ model.name | upper }}_NPHI -#define NHN {{ model.name | upper }}_NHN -#define NPHIN {{ model.name | upper }}_NPHIN -#define NR {{ model.name | upper }}_NR - - -int main() -{ - - {{ model.name }}_solver_capsule *acados_ocp_capsule = {{ model.name }}_acados_create_capsule(); - // there is an opportunity to change the number of shooting intervals in C without new code generation - int N = {{ model.name | upper }}_N; - // allocate the array and fill it accordingly - double* new_time_steps = NULL; - int status = {{ model.name }}_acados_create_with_discretization(acados_ocp_capsule, N, new_time_steps); - - if (status) - { - printf("{{ model.name }}_acados_create() returned status %d. Exiting.\n", status); - exit(1); - } - - ocp_nlp_config *nlp_config = {{ model.name }}_acados_get_nlp_config(acados_ocp_capsule); - ocp_nlp_dims *nlp_dims = {{ model.name }}_acados_get_nlp_dims(acados_ocp_capsule); - ocp_nlp_in *nlp_in = {{ model.name }}_acados_get_nlp_in(acados_ocp_capsule); - ocp_nlp_out *nlp_out = {{ model.name }}_acados_get_nlp_out(acados_ocp_capsule); - ocp_nlp_solver *nlp_solver = {{ model.name }}_acados_get_nlp_solver(acados_ocp_capsule); - void *nlp_opts = {{ model.name }}_acados_get_nlp_opts(acados_ocp_capsule); - - // initial condition - int idxbx0[NBX0]; - {%- for i in range(end=dims.nbx_0) %} - idxbx0[{{ i }}] = {{ constraints.idxbx_0[i] }}; - {%- endfor %} - - double lbx0[NBX0]; - double ubx0[NBX0]; - {%- for i in range(end=dims.nbx_0) %} - lbx0[{{ i }}] = {{ constraints.lbx_0[i] }}; - ubx0[{{ i }}] = {{ constraints.ubx_0[i] }}; - {%- endfor %} - - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "idxbx", idxbx0); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "lbx", lbx0); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "ubx", ubx0); - - // initialization for state values - double x_init[NX]; - {%- for i in range(end=dims.nx) %} - x_init[{{ i }}] = 0.0; - {%- endfor %} - - // initial value for control input - double u0[NU]; - {%- for i in range(end=dims.nu) %} - u0[{{ i }}] = 0.0; - {%- endfor %} - - - {%- if dims.np > 0 %} - // set parameters - double p[NP]; - {%- for item in parameter_values %} - p[{{ loop.index0 }}] = {{ item }}; - {%- endfor %} - - for (int ii = 0; ii <= N; ii++) - { - {{ model.name }}_acados_update_params(acados_ocp_capsule, ii, p, NP); - } - {% endif %}{# if np > 0 #} - - // prepare evaluation - int NTIMINGS = 1; - double min_time = 1e12; - double kkt_norm_inf; - double elapsed_time; - int sqp_iter; - - double xtraj[NX * (N+1)]; - double utraj[NU * N]; - - - // solve ocp in loop - int rti_phase = 0; - - for (int ii = 0; ii < NTIMINGS; ii++) - { - // initialize solution - for (int i = 0; i < N; i++) - { - ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "x", x_init); - ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "u", u0); - } - ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, N, "x", x_init); - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "rti_phase", &rti_phase); - status = {{ model.name }}_acados_solve(acados_ocp_capsule); - ocp_nlp_get(nlp_config, nlp_solver, "time_tot", &elapsed_time); - min_time = MIN(elapsed_time, min_time); - } - - /* print solution and statistics */ - for (int ii = 0; ii <= nlp_dims->N; ii++) - ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, ii, "x", &xtraj[ii*NX]); - for (int ii = 0; ii < nlp_dims->N; ii++) - ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, ii, "u", &utraj[ii*NU]); - - printf("\n--- xtraj ---\n"); - d_print_exp_tran_mat( NX, N+1, xtraj, NX); - printf("\n--- utraj ---\n"); - d_print_exp_tran_mat( NU, N, utraj, NU ); - // ocp_nlp_out_print(nlp_solver->dims, nlp_out); - - printf("\nsolved ocp %d times, solution printed above\n\n", NTIMINGS); - - if (status == ACADOS_SUCCESS) - { - printf("{{ model.name }}_acados_solve(): SUCCESS!\n"); - } - else - { - printf("{{ model.name }}_acados_solve() failed with status %d.\n", status); - } - - -{%- if custom_update_filename != "" %} - {{ model.name }}_acados_custom_update(acados_ocp_capsule, xtraj, NX*(N+1)); -{%- endif %} - - // get solution - ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, 0, "kkt_norm_inf", &kkt_norm_inf); - ocp_nlp_get(nlp_config, nlp_solver, "sqp_iter", &sqp_iter); - - {{ model.name }}_acados_print_stats(acados_ocp_capsule); - - printf("\nSolver info:\n"); - printf(" SQP iterations %2d\n minimum time for %d solve %f [ms]\n KKT %e\n", - sqp_iter, NTIMINGS, min_time*1000, kkt_norm_inf); - - // free solver - status = {{ model.name }}_acados_free(acados_ocp_capsule); - if (status) { - printf("{{ model.name }}_acados_free() returned status %d. \n", status); - } - // free solver capsule - status = {{ model.name }}_acados_free_capsule(acados_ocp_capsule); - if (status) { - printf("{{ model.name }}_acados_free_capsule() returned status %d. \n", status); - } - - return status; -} diff --git a/third_party/acados/acados_template/c_templates_tera/main_sim.in.c b/third_party/acados/acados_template/c_templates_tera/main_sim.in.c deleted file mode 100644 index 8960aa0035..0000000000 --- a/third_party/acados/acados_template/c_templates_tera/main_sim.in.c +++ /dev/null @@ -1,132 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -// standard -#include -#include -// acados -#include "acados/utils/print.h" -#include "acados/utils/math.h" -#include "acados_c/sim_interface.h" -#include "acados_sim_solver_{{ model.name }}.h" - -#define NX {{ model.name | upper }}_NX -#define NZ {{ model.name | upper }}_NZ -#define NU {{ model.name | upper }}_NU -#define NP {{ model.name | upper }}_NP - - -int main() -{ - int status = 0; - sim_solver_capsule *capsule = {{ model.name }}_acados_sim_solver_create_capsule(); - status = {{ model.name }}_acados_sim_create(capsule); - - if (status) - { - printf("acados_create() returned status %d. Exiting.\n", status); - exit(1); - } - - sim_config *acados_sim_config = {{ model.name }}_acados_get_sim_config(capsule); - sim_in *acados_sim_in = {{ model.name }}_acados_get_sim_in(capsule); - sim_out *acados_sim_out = {{ model.name }}_acados_get_sim_out(capsule); - void *acados_sim_dims = {{ model.name }}_acados_get_sim_dims(capsule); - - // initial condition - double x_current[NX]; - {%- for i in range(end=dims.nx) %} - x_current[{{ i }}] = 0.0; - {%- endfor %} - - {% if constraints.lbx_0 %} - {%- for i in range(end=dims.nbx_0) %} - x_current[{{ constraints.idxbx_0[i] }}] = {{ constraints.lbx_0[i] }}; - {%- endfor %} - {% if dims.nbx_0 != dims.nx %} - printf("main_sim: NOTE: initial state not fully defined via lbx_0, using 0.0 for indices that are not in idxbx_0."); - {%- endif %} - {% else %} - printf("main_sim: initial state not defined, should be in lbx_0, using zero vector."); - {%- endif %} - - - // initial value for control input - double u0[NU]; - {%- for i in range(end=dims.nu) %} - u0[{{ i }}] = 0.0; - {%- endfor %} - - {%- if dims.np > 0 %} - // set parameters - double p[NP]; - {%- for item in parameter_values %} - p[{{ loop.index0 }}] = {{ item }}; - {%- endfor %} - - {{ model.name }}_acados_sim_update_params(capsule, p, NP); - {% endif %}{# if np > 0 #} - - int n_sim_steps = 3; - // solve ocp in loop - for (int ii = 0; ii < n_sim_steps; ii++) - { - sim_in_set(acados_sim_config, acados_sim_dims, - acados_sim_in, "x", x_current); - status = {{ model.name }}_acados_sim_solve(capsule); - - if (status != ACADOS_SUCCESS) - { - printf("acados_solve() failed with status %d.\n", status); - } - - sim_out_get(acados_sim_config, acados_sim_dims, - acados_sim_out, "x", x_current); - - printf("\nx_current, %d\n", ii); - for (int jj = 0; jj < NX; jj++) - { - printf("%e\n", x_current[jj]); - } - } - - printf("\nPerformed %d simulation steps with acados integrator successfully.\n\n", n_sim_steps); - - // free solver - status = {{ model.name }}_acados_sim_free(capsule); - if (status) { - printf("{{ model.name }}_acados_sim_free() returned status %d. \n", status); - } - - {{ model.name }}_acados_sim_solver_free_capsule(capsule); - - return status; -} diff --git a/third_party/acados/acados_template/c_templates_tera/matlab_templates/acados_mex_create.in.c b/third_party/acados/acados_template/c_templates_tera/matlab_templates/acados_mex_create.in.c deleted file mode 100644 index 24ae94ac2c..0000000000 --- a/third_party/acados/acados_template/c_templates_tera/matlab_templates/acados_mex_create.in.c +++ /dev/null @@ -1,384 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -// standard -#include -#include -#include - -// acados -#include "acados/utils/print.h" -#include "acados_c/ocp_nlp_interface.h" -#include "acados_solver_{{ model.name }}.h" - -// mex -#include "mex.h" - - -void mexFunction(int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[]) -{ - long long *l_ptr; - int status = 0; - - // create solver - {{ model.name }}_solver_capsule *acados_ocp_capsule = {{ model.name }}_acados_create_capsule(); - - status = {{ model.name }}_acados_create(acados_ocp_capsule); - - if (status) - { - mexPrintf("{{ model.name }}_acados_create() returned status %d.\n", status); - } - mexPrintf("{{ model.name }}_acados_create() -> success!\n"); - - // get pointers to nlp solver related objects - ocp_nlp_plan_t *nlp_plan = {{ model.name }}_acados_get_nlp_plan(acados_ocp_capsule); - ocp_nlp_config *nlp_config = {{ model.name }}_acados_get_nlp_config(acados_ocp_capsule); - ocp_nlp_dims *nlp_dims = {{ model.name }}_acados_get_nlp_dims(acados_ocp_capsule); - ocp_nlp_in *nlp_in = {{ model.name }}_acados_get_nlp_in(acados_ocp_capsule); - ocp_nlp_out *nlp_out = {{ model.name }}_acados_get_nlp_out(acados_ocp_capsule); - ocp_nlp_solver *nlp_solver = {{ model.name }}_acados_get_nlp_solver(acados_ocp_capsule); - void *nlp_opts = {{ model.name }}_acados_get_nlp_opts(acados_ocp_capsule); - - // mexPrintf("acados: got pointer to objectes!\n"); - - // field names of output struct - #define FIELDS_OCP 9 - #define FIELDS_EXT_FUN 25 - #define MAX_FIELDS 25 - char *fieldnames[MAX_FIELDS]; - - for (int i = 0; i < MAX_FIELDS; i++) - { - fieldnames[i] = (char*) mxMalloc(50); - } - - memcpy(fieldnames[0],"config",sizeof("config")); - memcpy(fieldnames[1],"dims",sizeof("dims")); - memcpy(fieldnames[2],"opts",sizeof("opts")); - memcpy(fieldnames[3],"in",sizeof("in")); - memcpy(fieldnames[4],"out",sizeof("out")); - memcpy(fieldnames[5],"solver",sizeof("solver")); - memcpy(fieldnames[6],"sens_out",sizeof("sens_out")); - memcpy(fieldnames[7],"plan",sizeof("plan")); - memcpy(fieldnames[8],"capsule",sizeof("capsule")); - - // create output struct - C_ocp - plhs[0] = mxCreateStructMatrix(1, 1, 9, (const char **) fieldnames); - - // MEX: config, dims, opts, in, out, solver, sens_out, plan - // plan - mxArray *plan_mat = mxCreateNumericMatrix(1, 1, mxINT64_CLASS, mxREAL); - l_ptr = mxGetData(plan_mat); - l_ptr[0] = (long long) nlp_plan; - mxSetField(plhs[0], 0, "plan", plan_mat); - - // config - mxArray *config_mat = mxCreateNumericMatrix(1, 1, mxINT64_CLASS, mxREAL); - l_ptr = mxGetData(config_mat); - l_ptr[0] = (long long) nlp_config; - mxSetField(plhs[0], 0, "config", config_mat); - - // dims - mxArray *dims_mat = mxCreateNumericMatrix(1, 1, mxINT64_CLASS, mxREAL); - l_ptr = mxGetData(dims_mat); - l_ptr[0] = (long long) nlp_dims; - mxSetField(plhs[0], 0, "dims", dims_mat); - - // opts - mxArray *opts_mat = mxCreateNumericMatrix(1, 1, mxINT64_CLASS, mxREAL); - l_ptr = mxGetData(opts_mat); - l_ptr[0] = (long long) nlp_opts; - mxSetField(plhs[0], 0, "opts", opts_mat); - - // in - mxArray *in_mat = mxCreateNumericMatrix(1, 1, mxINT64_CLASS, mxREAL); - l_ptr = mxGetData(in_mat); - l_ptr[0] = (long long) nlp_in; - mxSetField(plhs[0], 0, "in", in_mat); - - // out - mxArray *out_mat = mxCreateNumericMatrix(1, 1, mxINT64_CLASS, mxREAL); - l_ptr = mxGetData(out_mat); - l_ptr[0] = (long long) nlp_out; - mxSetField(plhs[0], 0, "out", out_mat); - - // solver - mxArray *solver_mat = mxCreateNumericMatrix(1, 1, mxINT64_CLASS, mxREAL); - l_ptr = mxGetData(solver_mat); - l_ptr[0] = (long long) nlp_solver; - mxSetField(plhs[0], 0, "solver", solver_mat); - - // TODO: sens_out not actually implemented in templates.. - // sens_out - mxArray *sens_out_mat = mxCreateNumericMatrix(1, 1, mxINT64_CLASS, mxREAL); - l_ptr = mxGetData(sens_out_mat); - l_ptr[0] = (long long) 1; - mxSetField(plhs[0], 0, "sens_out", sens_out_mat); - - // capsule - mxArray *capsule_mat = mxCreateNumericMatrix(1, 1, mxINT64_CLASS, mxREAL); - l_ptr = mxGetData(capsule_mat); - l_ptr[0] = (long long) acados_ocp_capsule; - mxSetField(plhs[0], 0, "capsule", capsule_mat); - - /* store external function pointers */ - // dyn - memcpy(fieldnames[0],"expl_ode_fun",sizeof("expl_ode_fun")); - memcpy(fieldnames[1],"forw_vde",sizeof("forw_vde")); - memcpy(fieldnames[2],"hess_vde",sizeof("hess_vde")); - memcpy(fieldnames[3],"impl_dae_fun",sizeof("impl_dae_fun")); - memcpy(fieldnames[4],"impl_dae_fun_jac_x_xdot_z",sizeof("impl_dae_fun_jac_x_xdot_z")); - memcpy(fieldnames[5],"impl_dae_jac_x_xdot_u_z",sizeof("impl_dae_jac_x_xdot_u_z")); - memcpy(fieldnames[6],"impl_dae_hess",sizeof("impl_dae_hess")); - - memcpy(fieldnames[7],"gnsf_phi_fun",sizeof("gnsf_phi_fun")); - memcpy(fieldnames[8],"gnsf_phi_fun_jac_y",sizeof("gnsf_phi_fun_jac_y")); - memcpy(fieldnames[9],"gnsf_phi_jac_y_uhat",sizeof("gnsf_phi_jac_y_uhat")); - memcpy(fieldnames[10],"gnsf_f_lo_jac_x1_x1dot_u_z",sizeof("gnsf_f_lo_jac_x1_x1dot_u_z")); - memcpy(fieldnames[11],"gnsf_get_matrices_fun",sizeof("gnsf_get_matrices_fun")); - - memcpy(fieldnames[12],"disc_phi_fun",sizeof("disc_phi_fun")); - memcpy(fieldnames[13],"disc_phi_fun_jac",sizeof("disc_phi_fun_jac")); - memcpy(fieldnames[14],"disc_phi_fun_jac_hess",sizeof("disc_phi_fun_jac_hess")); - - // cost - memcpy(fieldnames[15],"cost_y_fun",sizeof("cost_y_fun")); - memcpy(fieldnames[16],"cost_y_fun_jac_ut_xt",sizeof("cost_y_fun_jac_ut_xt")); - memcpy(fieldnames[17],"cost_y_hess",sizeof("cost_y_hess")); - memcpy(fieldnames[18],"ext_cost_fun",sizeof("ext_cost_fun")); - memcpy(fieldnames[19],"ext_cost_fun_jac",sizeof("ext_cost_fun_jac")); - memcpy(fieldnames[20],"ext_cost_fun_jac_hess",sizeof("ext_cost_fun_jac_hess")); - - // constraints - memcpy(fieldnames[21],"phi_constraint",sizeof("phi_constraint")); - memcpy(fieldnames[22],"nl_constr_h_fun_jac",sizeof("nl_constr_h_fun_jac")); - memcpy(fieldnames[23],"nl_constr_h_fun",sizeof("nl_constr_h_fun")); - memcpy(fieldnames[24],"nl_constr_h_fun_jac_hess",sizeof("nl_constr_h_fun_jac_hess")); - - - // create output struct - C_ocp_ext_fun - plhs[1] = mxCreateStructMatrix(1, 1, FIELDS_EXT_FUN, (const char **) fieldnames); - - - for (int i = 0; i < FIELDS_EXT_FUN; i++) - { - mxFree( fieldnames[i] ); - } - -/* dynamics */ - mxArray *expl_ode_fun_mat = mxCreateNumericMatrix(1, 1, mxINT64_CLASS, mxREAL); - mxArray *forw_vde_mat = mxCreateNumericMatrix(1, 1, mxINT64_CLASS, mxREAL); - mxArray *hess_vde_mat = mxCreateNumericMatrix(1, 1, mxINT64_CLASS, mxREAL); - mxArray *impl_dae_fun_mat = mxCreateNumericMatrix(1, 1, mxINT64_CLASS, mxREAL); - mxArray *impl_dae_fun_jac_x_xdot_z_mat = mxCreateNumericMatrix(1, 1, mxINT64_CLASS, mxREAL); - mxArray *impl_dae_jac_x_xdot_u_z_mat = mxCreateNumericMatrix(1, 1, mxINT64_CLASS, mxREAL); - mxArray *impl_dae_hess_mat = mxCreateNumericMatrix(1, 1, mxINT64_CLASS, mxREAL); - - mxArray *gnsf_phi_fun_mat = mxCreateNumericMatrix(1, 1, mxINT64_CLASS, mxREAL); - mxArray *gnsf_phi_fun_jac_y_mat = mxCreateNumericMatrix(1, 1, mxINT64_CLASS, mxREAL); - mxArray *gnsf_phi_jac_y_uhat_mat = mxCreateNumericMatrix(1, 1, mxINT64_CLASS, mxREAL); - mxArray *gnsf_f_lo_jac_x1_x1dot_u_z_mat = mxCreateNumericMatrix(1, 1, mxINT64_CLASS, mxREAL); - mxArray *gnsf_get_matrices_fun_mat = mxCreateNumericMatrix(1, 1, mxINT64_CLASS, mxREAL); - - mxArray *disc_phi_fun_mat = mxCreateNumericMatrix(1, 1, mxINT64_CLASS, mxREAL); - mxArray *disc_phi_fun_jac_mat = mxCreateNumericMatrix(1, 1, mxINT64_CLASS, mxREAL); - mxArray *disc_phi_fun_jac_hess_mat = mxCreateNumericMatrix(1, 1, mxINT64_CLASS, mxREAL); - -{% if solver_options.integrator_type == "ERK" %} - {# TODO: remove _casadi from these names.. #} - l_ptr = mxGetData(forw_vde_mat); - l_ptr[0] = (long long) acados_ocp_capsule->forw_vde_casadi; - l_ptr = mxGetData(expl_ode_fun_mat); - l_ptr[0] = (long long) acados_ocp_capsule->expl_ode_fun; -{% if solver_options.hessian_approx == "EXACT" %} - l_ptr = mxGetData(hess_vde_mat); - l_ptr[0] = (long long) acados_ocp_capsule->hess_vde_casadi; -{%- endif %} -{% elif solver_options.integrator_type == "IRK" %} - l_ptr = mxGetData(impl_dae_fun_mat); - l_ptr[0] = (long long) acados_ocp_capsule->impl_dae_fun; - l_ptr = mxGetData(impl_dae_fun_jac_x_xdot_z_mat); - l_ptr[0] = (long long) acados_ocp_capsule->impl_dae_fun_jac_x_xdot_z; - l_ptr = mxGetData(impl_dae_jac_x_xdot_u_z_mat); - l_ptr[0] = (long long) acados_ocp_capsule->impl_dae_jac_x_xdot_u_z; -{% if solver_options.hessian_approx == "EXACT" %} - l_ptr = mxGetData(impl_dae_hess_mat); - l_ptr[0] = (long long) acados_ocp_capsule->impl_dae_hess; -{%- endif %} -{% elif solver_options.integrator_type == "GNSF" %} - {% if model.gnsf.purely_linear != 1 %} - l_ptr = mxGetData(gnsf_phi_fun_mat); - l_ptr[0] = (long long) acados_ocp_capsule->gnsf_phi_fun; - l_ptr = mxGetData(gnsf_phi_fun_jac_y_mat); - l_ptr[0] = (long long) acados_ocp_capsule->gnsf_phi_fun_jac_y; - l_ptr = mxGetData(gnsf_phi_jac_y_uhat_mat); - l_ptr[0] = (long long) acados_ocp_capsule->gnsf_phi_jac_y_uhat; - {% if model.gnsf.nontrivial_f_LO == 1 %} - l_ptr = mxGetData(gnsf_f_lo_jac_x1_x1dot_u_z_mat); - l_ptr[0] = (long long) acados_ocp_capsule->gnsf_f_lo_jac_x1_x1dot_u_z; - {%- endif %} - {%- endif %} - l_ptr = mxGetData(gnsf_get_matrices_fun_mat); - l_ptr[0] = (long long) acados_ocp_capsule->gnsf_get_matrices_fun; -{% elif solver_options.integrator_type == "DISCRETE" %} - l_ptr = mxGetData(disc_phi_fun_mat); - l_ptr[0] = (long long) acados_ocp_capsule->discr_dyn_phi_fun; - l_ptr = mxGetData(disc_phi_fun_jac_mat); - l_ptr[0] = (long long) acados_ocp_capsule->discr_dyn_phi_fun_jac_ut_xt; -{% if solver_options.hessian_approx == "EXACT" %} - l_ptr = mxGetData(disc_phi_fun_jac_hess_mat); - l_ptr[0] = (long long) acados_ocp_capsule->discr_dyn_phi_fun_jac_ut_xt_hess; -{%- endif %} -{%- endif %} - mxSetField(plhs[1], 0, "expl_ode_fun", expl_ode_fun_mat); - mxSetField(plhs[1], 0, "forw_vde", forw_vde_mat); - mxSetField(plhs[1], 0, "hess_vde", hess_vde_mat); - - mxSetField(plhs[1], 0, "gnsf_phi_fun", gnsf_phi_fun_mat); - mxSetField(plhs[1], 0, "gnsf_phi_fun_jac_y", gnsf_phi_fun_jac_y_mat); - mxSetField(plhs[1], 0, "gnsf_phi_jac_y_uhat", gnsf_phi_jac_y_uhat_mat); - mxSetField(plhs[1], 0, "gnsf_f_lo_jac_x1_x1dot_u_z", gnsf_f_lo_jac_x1_x1dot_u_z_mat); - mxSetField(plhs[1], 0, "gnsf_get_matrices_fun", gnsf_get_matrices_fun_mat); - - mxSetField(plhs[1], 0, "impl_dae_fun", impl_dae_fun_mat); - mxSetField(plhs[1], 0, "impl_dae_fun_jac_x_xdot_z", impl_dae_fun_jac_x_xdot_z_mat); - mxSetField(plhs[1], 0, "impl_dae_jac_x_xdot_u_z", impl_dae_jac_x_xdot_u_z_mat); - mxSetField(plhs[1], 0, "impl_dae_hess", impl_dae_hess_mat); - - mxSetField(plhs[1], 0, "disc_phi_fun", disc_phi_fun_mat); - mxSetField(plhs[1], 0, "disc_phi_fun_jac", disc_phi_fun_jac_mat); - mxSetField(plhs[1], 0, "disc_phi_fun_jac_hess", disc_phi_fun_jac_hess_mat); -/* constaints */ - mxArray *phi_constraint_mat = mxCreateNumericMatrix(1, 2, mxINT64_CLASS, mxREAL); - l_ptr = mxGetData(phi_constraint_mat); -{%- if constraints.constr_type == "BGP" %} - l_ptr[0] = (long long) acados_ocp_capsule->phi_constraint; -{% endif %} -{% if constraints.constr_type_e == "BGP" %} - l_ptr[1] = (long long) &acados_ocp_capsule->phi_e_constraint; -{% endif %} - mxSetField(plhs[1], 0, "phi_constraint", phi_constraint_mat); - - mxArray *nl_constr_h_fun_jac_mat = mxCreateNumericMatrix(1, 2, mxINT64_CLASS, mxREAL); - l_ptr = mxGetData(nl_constr_h_fun_jac_mat); -{% if constraints.constr_type == "BGH" and dims.nh > 0 %} - l_ptr[0] = (long long) acados_ocp_capsule->nl_constr_h_fun_jac; -{% endif %} -{% if constraints.constr_type_e == "BGH" and dims.nh_e > 0 %} - l_ptr[1] = (long long) &acados_ocp_capsule->nl_constr_h_e_fun_jac; -{%- endif %} - mxSetField(plhs[1], 0, "nl_constr_h_fun_jac", nl_constr_h_fun_jac_mat); - - mxArray *nl_constr_h_fun_mat = mxCreateNumericMatrix(1, 2, mxINT64_CLASS, mxREAL); - l_ptr = mxGetData(nl_constr_h_fun_mat); -{% if constraints.constr_type == "BGH" and dims.nh > 0 %} - l_ptr[0] = (long long) acados_ocp_capsule->nl_constr_h_fun; -{% endif %} -{% if constraints.constr_type_e == "BGH" and dims.nh_e > 0 %} - l_ptr[1] = (long long) &acados_ocp_capsule->nl_constr_h_e_fun; -{%- endif %} - mxSetField(plhs[1], 0, "nl_constr_h_fun", nl_constr_h_fun_mat); - - mxArray *nl_constr_h_fun_jac_hess_mat = mxCreateNumericMatrix(1, 2, mxINT64_CLASS, mxREAL); - l_ptr = mxGetData(nl_constr_h_fun_jac_hess_mat); -{% if constraints.constr_type == "BGH" and dims.nh > 0 and solver_options.hessian_approx == "EXACT" %} - l_ptr[0] = (long long) acados_ocp_capsule->nl_constr_h_fun_jac_hess; -{% endif %} -{% if constraints.constr_type_e == "BGH" and dims.nh_e > 0 and solver_options.hessian_approx == "EXACT" %} - l_ptr[1] = (long long) &acados_ocp_capsule->nl_constr_h_e_fun_jac_hess; -{%- endif %} - mxSetField(plhs[1], 0, "nl_constr_h_fun_jac_hess", nl_constr_h_fun_jac_hess_mat); - -/* cost */ - mxArray *cost_y_fun_mat = mxCreateNumericMatrix(1, 2, mxINT64_CLASS, mxREAL); - l_ptr = mxGetData(cost_y_fun_mat); -{% if cost.cost_type == "NONLINEAR_LS" %} - l_ptr[0] = (long long) acados_ocp_capsule->cost_y_fun; -{% endif %} -{% if cost.cost_type_e == "NONLINEAR_LS" %} - l_ptr[1] = (long long) &acados_ocp_capsule->cost_y_e_fun; -{%- endif %} - mxSetField(plhs[1], 0, "cost_y_fun", cost_y_fun_mat); - - mxArray *cost_y_fun_jac_ut_xt_mat = mxCreateNumericMatrix(1, 2, mxINT64_CLASS, mxREAL); - l_ptr = mxGetData(cost_y_fun_jac_ut_xt_mat); -{% if cost.cost_type == "NONLINEAR_LS" %} - l_ptr[0] = (long long) acados_ocp_capsule->cost_y_fun_jac_ut_xt; -{% endif %} -{% if cost.cost_type_e == "NONLINEAR_LS" %} - l_ptr[1] = (long long) &acados_ocp_capsule->cost_y_e_fun_jac_ut_xt; -{%- endif %} - mxSetField(plhs[1], 0, "cost_y_fun_jac_ut_xt", cost_y_fun_jac_ut_xt_mat); - - mxArray *cost_y_hess_mat = mxCreateNumericMatrix(1, 2, mxINT64_CLASS, mxREAL); - l_ptr = mxGetData(cost_y_hess_mat); -{% if cost.cost_type == "NONLINEAR_LS" %} - l_ptr[0] = (long long) acados_ocp_capsule->cost_y_hess; -{% endif %} -{% if cost.cost_type_e == "NONLINEAR_LS" %} - l_ptr[1] = (long long) &acados_ocp_capsule->cost_y_e_hess; -{%- endif %} - mxSetField(plhs[1], 0, "cost_y_hess", cost_y_hess_mat); - - mxArray *ext_cost_fun_mat = mxCreateNumericMatrix(1, 2, mxINT64_CLASS, mxREAL); - l_ptr = mxGetData(ext_cost_fun_mat); -{% if cost.cost_type == "EXTERNAL" %} - l_ptr[0] = (long long) acados_ocp_capsule->ext_cost_fun; -{% endif -%} -{% if cost.cost_type_e == "EXTERNAL" %} - l_ptr[1] = (long long) &acados_ocp_capsule->ext_cost_e_fun; -{%- endif %} - mxSetField(plhs[1], 0, "ext_cost_fun", ext_cost_fun_mat); - - mxArray *ext_cost_fun_jac_mat = mxCreateNumericMatrix(1, 2, mxINT64_CLASS, mxREAL); - l_ptr = mxGetData(ext_cost_fun_jac_mat); -{% if cost.cost_type == "EXTERNAL" %} - l_ptr[0] = (long long) acados_ocp_capsule->ext_cost_fun_jac; -{% endif -%} -{% if cost.cost_type_e == "EXTERNAL" %} - l_ptr[1] = (long long) &acados_ocp_capsule->ext_cost_e_fun_jac; -{%- endif %} - mxSetField(plhs[1], 0, "ext_cost_fun_jac", ext_cost_fun_jac_mat); - - mxArray *ext_cost_fun_jac_hess_mat = mxCreateNumericMatrix(1, 2, mxINT64_CLASS, mxREAL); - l_ptr = mxGetData(ext_cost_fun_jac_hess_mat); -{% if cost.cost_type == "EXTERNAL" %} - l_ptr[0] = (long long) acados_ocp_capsule->ext_cost_fun_jac_hess; -{% endif -%} -{% if cost.cost_type_e == "EXTERNAL" %} - l_ptr[1] = (long long) &acados_ocp_capsule->ext_cost_e_fun_jac_hess; -{%- endif %} - mxSetField(plhs[1], 0, "ext_cost_fun_jac_hess", ext_cost_fun_jac_hess_mat); - - - return; -} diff --git a/third_party/acados/acados_template/c_templates_tera/matlab_templates/acados_mex_free.in.c b/third_party/acados/acados_template/c_templates_tera/matlab_templates/acados_mex_free.in.c deleted file mode 100644 index bd457969b2..0000000000 --- a/third_party/acados/acados_template/c_templates_tera/matlab_templates/acados_mex_free.in.c +++ /dev/null @@ -1,67 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - -// system -#include -#include -#include -// acados -#include "acados_solver_{{ model.name }}.h" - -// mex -#include "mex.h" - - -void mexFunction(int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[]) -{ - int status = 0; - long long *ptr; - - // mexPrintf("\nin mex_acados_free\n"); - const mxArray *C_ocp = prhs[0]; - // capsule - ptr = (long long *) mxGetData( mxGetField( C_ocp, 0, "capsule" ) ); - {{ model.name }}_solver_capsule *capsule = ({{ model.name }}_solver_capsule *) ptr[0]; - - status = {{ model.name }}_acados_free(capsule); - if (status) - { - mexPrintf("{{ model.name }}_acados_free() returned status %d.\n", status); - } - - status = {{ model.name }}_acados_free_capsule(capsule); - if (status) - { - mexPrintf("{{ model.name }}_acados_free_capsule() returned status %d.\n", status); - } - - return; -} - diff --git a/third_party/acados/acados_template/c_templates_tera/matlab_templates/acados_mex_set.in.c b/third_party/acados/acados_template/c_templates_tera/matlab_templates/acados_mex_set.in.c deleted file mode 100644 index 78a308df49..0000000000 --- a/third_party/acados/acados_template/c_templates_tera/matlab_templates/acados_mex_set.in.c +++ /dev/null @@ -1,632 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -// standard -#include -#include -#include - -// acados -#include "acados/utils/print.h" -#include "acados_c/ocp_nlp_interface.h" -#include "acados_solver_{{ model.name }}.h" - -// mex -#include "mex.h" -#include "mex_macros.h" - - -void mexFunction(int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[]) -{ - - long long *ptr; - int acados_size; - mxArray *mex_field; - char fun_name[20] = "ocp_set"; - char buffer [500]; // for error messages - - /* RHS */ - int min_nrhs = 6; - - // C ocp - const mxArray *C_ocp = prhs[2]; - // capsule - ptr = (long long *) mxGetData( mxGetField( C_ocp, 0, "capsule" ) ); - {{ model.name }}_solver_capsule *capsule = ({{ model.name }}_solver_capsule *) ptr[0]; - // plan - ptr = (long long *) mxGetData( mxGetField( C_ocp, 0, "plan" ) ); - ocp_nlp_plan_t *plan = (ocp_nlp_plan_t *) ptr[0]; - // config - ptr = (long long *) mxGetData( mxGetField( C_ocp, 0, "config" ) ); - ocp_nlp_config *config = (ocp_nlp_config *) ptr[0]; - // dims - ptr = (long long *) mxGetData( mxGetField( C_ocp, 0, "dims" ) ); - ocp_nlp_dims *dims = (ocp_nlp_dims *) ptr[0]; - // opts - ptr = (long long *) mxGetData( mxGetField( C_ocp, 0, "opts" ) ); - void *opts = (void *) ptr[0]; - // in - ptr = (long long *) mxGetData( mxGetField( C_ocp, 0, "in" ) ); - ocp_nlp_in *in = (ocp_nlp_in *) ptr[0]; - // out - ptr = (long long *) mxGetData( mxGetField( C_ocp, 0, "out" ) ); - ocp_nlp_out *out = (ocp_nlp_out *) ptr[0]; - // solver - ptr = (long long *) mxGetData( mxGetField( C_ocp, 0, "solver" ) ); - ocp_nlp_solver *solver = (ocp_nlp_solver *) ptr[0]; - - const mxArray *C_ext_fun_pointers = prhs[3]; - // field - char *field = mxArrayToString( prhs[4] ); - // value - double *value = mxGetPr( prhs[5] ); - - // for checks - int matlab_size = (int) mxGetNumberOfElements( prhs[5] ); - int nrow = (int) mxGetM( prhs[5] ); - int ncol = (int) mxGetN( prhs[5] ); - - int N = dims->N; - int nu = dims->nu[0]; - int nx = dims->nx[0]; - - // stage - int s0, se; - if (nrhs==min_nrhs) - { - s0 = 0; - se = N; - } - else if (nrhs==min_nrhs+1) - { - s0 = mxGetScalar( prhs[6] ); - if (s0 > N) - { - sprintf(buffer, "ocp_set: N < specified stage = %d\n", s0); - mexErrMsgTxt(buffer); - } - se = s0 + 1; - } - else - { - sprintf(buffer, "ocp_set: wrong nrhs: %d\n", nrhs); - mexErrMsgTxt(buffer); - } - - /* Set value */ - // constraints - if (!strcmp(field, "constr_x0")) - { - acados_size = nx; - MEX_DIM_CHECK_VEC(fun_name, field, matlab_size, acados_size); - ocp_nlp_constraints_model_set(config, dims, in, 0, "lbx", value); - ocp_nlp_constraints_model_set(config, dims, in, 0, "ubx", value); - } - else if (!strcmp(field, "constr_C")) - { - for (int ii=s0; iinlp_cost[ii] == LINEAR_LS) || (plan->nlp_cost[ii] == NONLINEAR_LS)) - { - acados_size = ocp_nlp_dims_get_from_attr(config, dims, out, ii, "y_ref"); - MEX_DIM_CHECK_VEC(fun_name, field, matlab_size, acados_size); - ocp_nlp_cost_model_set(config, dims, in, ii, "y_ref", value); - } - else - { - MEX_FIELD_NOT_SUPPORTED_FOR_COST_STAGE(fun_name, field, plan->nlp_cost[ii], ii); - } - } - } - else if (!strcmp(field, "cost_y_ref_e")) - { - acados_size = ocp_nlp_dims_get_from_attr(config, dims, out, N, "y_ref"); - MEX_DIM_CHECK_VEC(fun_name, field, matlab_size, acados_size); - ocp_nlp_cost_model_set(config, dims, in, N, "y_ref", value); - } - else if (!strcmp(field, "cost_Vu")) - { - for (int ii=s0; iinlp_cost[ii] == LINEAR_LS) || (plan->nlp_cost[ii] == NONLINEAR_LS)) - { - int ny = ocp_nlp_dims_get_from_attr(config, dims, out, ii, "y_ref"); - int nu = ocp_nlp_dims_get_from_attr(config, dims, out, ii, "u"); - acados_size = ny * nu; - MEX_DIM_CHECK_VEC(fun_name, field, matlab_size, acados_size); - ocp_nlp_cost_model_set(config, dims, in, ii, "Vu", value); - } - else - { - MEX_FIELD_NOT_SUPPORTED_FOR_COST_STAGE(fun_name, field, plan->nlp_cost[ii], ii); - } - } - } - else if (!strcmp(field, "cost_Vx")) - { - for (int ii=s0; iinlp_cost[ii] == LINEAR_LS) || (plan->nlp_cost[ii] == NONLINEAR_LS)) - { - int ny = ocp_nlp_dims_get_from_attr(config, dims, out, ii, "y_ref"); - int nx = ocp_nlp_dims_get_from_attr(config, dims, out, ii, "x"); - acados_size = ny * nx; - MEX_DIM_CHECK_VEC(fun_name, field, matlab_size, acados_size); - ocp_nlp_cost_model_set(config, dims, in, ii, "Vx", value); - } - else - { - MEX_FIELD_NOT_SUPPORTED_FOR_COST_STAGE(fun_name, field, plan->nlp_cost[ii], ii); - } - } - } - else if (!strcmp(field, "cost_W")) - { - for (int ii=s0; iinlp_cost[ii] == LINEAR_LS) || (plan->nlp_cost[ii] == NONLINEAR_LS)) - { - int ny = ocp_nlp_dims_get_from_attr(config, dims, out, s0, "y_ref"); - acados_size = ny * ny; - MEX_DIM_CHECK_VEC(fun_name, field, matlab_size, acados_size); - ocp_nlp_cost_model_set(config, dims, in, ii, "W", value); - } - else - { - MEX_FIELD_NOT_SUPPORTED_FOR_COST_STAGE(fun_name, field, plan->nlp_cost[ii], ii); - } - } - } - else if (!strcmp(field, "cost_Z")) - { - acados_size = ocp_nlp_dims_get_from_attr(config, dims, out, s0, "cost_Z"); - MEX_DIM_CHECK_VEC(fun_name, field, matlab_size, acados_size); - for (int ii=s0; iisim_solver_plan[0]; - sim_solver_t type = sim_plan.sim_solver; - if (type == IRK) - { - int nz = ocp_nlp_dims_get_from_attr(config, dims, out, 0, "z"); - if (nrhs==min_nrhs) - { - acados_size = N*nz; - MEX_DIM_CHECK_VEC(fun_name, field, matlab_size, acados_size); - for (int ii=0; iisim_solver_plan[0]; - sim_solver_t type = sim_plan.sim_solver; - if (type == IRK) - { - int nx = ocp_nlp_dims_get_from_attr(config, dims, out, 0, "x"); - if (nrhs==min_nrhs) - { - acados_size = N*nx; - MEX_DIM_CHECK_VEC(fun_name, field, matlab_size, acados_size); - for (int ii=0; iisim_solver_plan[0]; - sim_solver_t type = sim_plan.sim_solver; - if (type == GNSF) - { - int nout = ocp_nlp_dims_get_from_attr(config, dims, out, 0, "init_gnsf_phi"); - - if (nrhs==min_nrhs) - { - acados_size = N*nout; - MEX_DIM_CHECK_VEC(fun_name, field, matlab_size, acados_size); - for (int ii=0; iinlp_solver == SQP && rti_phase != 0) - { - MEX_FIELD_ONLY_SUPPORTED_FOR_SOLVER(fun_name, field, "sqp_rti") - } - ocp_nlp_solver_opts_set(config, opts, "rti_phase", &rti_phase); - } - else if (!strcmp(field, "qp_warm_start")) - { - acados_size = 1; - MEX_DIM_CHECK_VEC(fun_name, field, matlab_size, acados_size); - int qp_warm_start = (int) value[0]; - ocp_nlp_solver_opts_set(config, opts, "qp_warm_start", &qp_warm_start); - } - else if (!strcmp(field, "warm_start_first_qp")) - { - acados_size = 1; - MEX_DIM_CHECK_VEC(fun_name, field, matlab_size, acados_size); - int warm_start_first_qp = (int) value[0]; - ocp_nlp_solver_opts_set(config, opts, "warm_start_first_qp", &warm_start_first_qp); - } - else if (!strcmp(field, "print_level")) - { - acados_size = 1; - MEX_DIM_CHECK_VEC(fun_name, field, matlab_size, acados_size); - int print_level = (int) value[0]; - ocp_nlp_solver_opts_set(config, opts, "print_level", &print_level); - } - else - { - MEX_FIELD_NOT_SUPPORTED_SUGGEST(fun_name, field, "p, constr_x0,\ - constr_lbx, constr_ubx, constr_C, constr_D, constr_lg, constr_ug, constr_lh, constr_uh,\ - constr_lbu, constr_ubu, cost_y_ref[_e], sl, su, x, xdot, u, pi, lam, z, \ - cost_Vu, cost_Vx, cost_Vz, cost_W, cost_Z, cost_Zl, cost_Zu, cost_z,\ - cost_zl, cost_zu, init_x, init_u, init_z, init_xdot, init_gnsf_phi,\ - init_pi, nlp_solver_max_iter, qp_warm_start, warm_start_first_qp, print_level"); - } - - return; -} - diff --git a/third_party/acados/acados_template/c_templates_tera/matlab_templates/acados_mex_solve.in.c b/third_party/acados/acados_template/c_templates_tera/matlab_templates/acados_mex_solve.in.c deleted file mode 100644 index 300a440cc9..0000000000 --- a/third_party/acados/acados_template/c_templates_tera/matlab_templates/acados_mex_solve.in.c +++ /dev/null @@ -1,56 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - -// system -#include -#include -#include -// acados -#include "acados_solver_{{ model.name }}.h" - -// mex -#include "mex.h" - - - -void mexFunction(int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[]) -{ - // C_ocp - long long *ptr; - const mxArray *C_ocp = prhs[0]; - - // capsule - ptr = (long long *) mxGetData( mxGetField( C_ocp, 0, "capsule" ) ); - {{ model.name }}_solver_capsule *capsule = ({{ model.name }}_solver_capsule *) ptr[0]; - - // solve - {{ model.name }}_acados_solve(capsule); - -} diff --git a/third_party/acados/acados_template/c_templates_tera/matlab_templates/acados_sim_solver_sfun.in.c b/third_party/acados/acados_template/c_templates_tera/matlab_templates/acados_sim_solver_sfun.in.c deleted file mode 100644 index bd73ff69a4..0000000000 --- a/third_party/acados/acados_template/c_templates_tera/matlab_templates/acados_sim_solver_sfun.in.c +++ /dev/null @@ -1,230 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - -#define S_FUNCTION_NAME acados_sim_solver_sfunction_{{ model.name }} -#define S_FUNCTION_LEVEL 2 - -#define MDL_START - -// acados -// #include "acados/utils/print.h" -#include "acados_c/ocp_nlp_interface.h" -#include "acados_c/external_function_interface.h" - -// example specific -#include "{{ model.name }}_model/{{ model.name }}_model.h" -#include "acados_sim_solver_{{ model.name }}.h" - -#include "simstruc.h" - -#define SAMPLINGTIME {{ solver_options.Tsim }} - - -static void mdlInitializeSizes (SimStruct *S) -{ - // specify the number of continuous and discrete states - ssSetNumContStates(S, 0); - ssSetNumDiscStates(S, 0); - - {# compute number of input ports #} - {%- set n_inputs = 1 %} {# x0 #} - {%- if dims.nu > 0 %} {# u0 -#} - {%- set n_inputs = n_inputs + 1 -%} - {%- endif %} - {%- if dims.np > 0 %} {# parameters #} - {%- set n_inputs = n_inputs + 1 -%} - {%- endif %} - - // specify the number of input ports - if ( !ssSetNumInputPorts(S, {{ n_inputs }}) ) - return; - - // specify the number of output ports - if ( !ssSetNumOutputPorts(S, 1) ) - return; - - // specify dimension information for the input ports - {%- set i_input = 0 %} - // x0 - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.nx }}); - - {%- if dims.nu > 0 %} - {%- set i_input = i_input + 1 %} - // u0 - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.nu }}); - {%- endif %} - - {%- if dims.np > 0 %} - {%- set i_input = i_input + 1 %} - // parameters - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.np }}); - {%- endif %} - - // specify dimension information for the output ports - ssSetOutputPortVectorDimension(S, 0, {{ dims.nx }} ); // xnext - - // specify the direct feedthrough status - // should be set to 1 for all inputs used in mdlOutputs - {%- for i in range(end=n_inputs) %} - ssSetInputPortDirectFeedThrough(S, {{ i }}, 1); - {%- endfor %} - - // one sample time - ssSetNumSampleTimes(S, 1); -} - - -#if defined(MATLAB_MEX_FILE) - -#define MDL_SET_INPUT_PORT_DIMENSION_INFO -#define MDL_SET_OUTPUT_PORT_DIMENSION_INFO - -static void mdlSetInputPortDimensionInfo(SimStruct *S, int_T port, const DimsInfo_T *dimsInfo) -{ - if ( !ssSetInputPortDimensionInfo(S, port, dimsInfo) ) - return; -} - -static void mdlSetOutputPortDimensionInfo(SimStruct *S, int_T port, const DimsInfo_T *dimsInfo) -{ - if ( !ssSetOutputPortDimensionInfo(S, port, dimsInfo) ) - return; -} - -#endif /* MATLAB_MEX_FILE */ - - -static void mdlInitializeSampleTimes(SimStruct *S) -{ - ssSetSampleTime(S, 0, SAMPLINGTIME); - ssSetOffsetTime(S, 0, 0.0); -} - - -static void mdlStart(SimStruct *S) -{ - sim_solver_capsule *capsule = {{ model.name }}_acados_sim_solver_create_capsule(); - {{ model.name }}_acados_sim_create(capsule); - - ssSetUserData(S, (void*)capsule); -} - -static void mdlOutputs(SimStruct *S, int_T tid) -{ - sim_solver_capsule *capsule = ssGetUserData(S); - - sim_config *acados_sim_config = {{ model.name }}_acados_get_sim_config(capsule); - sim_in *acados_sim_in = {{ model.name }}_acados_get_sim_in(capsule); - sim_out *acados_sim_out = {{ model.name }}_acados_get_sim_out(capsule); - void *acados_sim_dims = {{ model.name }}_acados_get_sim_dims(capsule); - // sim_opts * {{ model.name }}_acados_get_sim_opts(capsule); - // sim_solver * {{ model.name }}_acados_get_sim_solver(capsule); - - InputRealPtrsType in_sign; - {% set input_sizes = [dims.nx, dims.nu, dims.np] %} - - // local buffer - {%- set buffer_size = input_sizes | sort | last %} - real_t buffer[{{ buffer_size }}]; - - - /* go through inputs */ - {%- set i_input = 0 %} - // initial condition - in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - for (int i = 0; i < {{ dims.nx }}; i++) - buffer[i] = (double)(*in_sign[i]); - - sim_in_set(acados_sim_config, acados_sim_dims, - acados_sim_in, "x", buffer); - - - // ssPrintf("\nin acados sim:\n"); - // for (int i = 0; i < {{ dims.nx }}; i++) ssPrintf("x0[%d] = %f\n", i, buffer[i]); - // ssPrintf("\n"); - -{% if dims.nu > 0 %} - // control input - u - {%- set i_input = i_input + 1 %} - in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - - for (int i = 0; i < {{ dims.nu }}; i++) - buffer[i] = (double)(*in_sign[i]); - - sim_in_set(acados_sim_config, acados_sim_dims, - acados_sim_in, "u", buffer); -{%- endif %} - - -{% if dims.np > 0 %} - // parameters - {%- set i_input = i_input + 1 %} - in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - - for (int i = 0; i < {{ dims.np }}; i++) - buffer[i] = (double)(*in_sign[i]); - - // update value of parameters - {{ model.name }}_acados_sim_update_params(capsule, buffer, {{ dims.np }}); -{%- endif %} - - - /* call solver */ - int acados_status = {{ model.name }}_acados_sim_solve(capsule); - - - /* set outputs */ - real_t *out_x = ssGetOutputPortRealSignal(S, 0); - - // get simulated state - sim_out_get(acados_sim_config, acados_sim_dims, acados_sim_out, - "xn", (void *) out_x); - - // ssPrintf("\nacados sim solve: returned %d\n", acados_status); - // for (int i = 0; i < {{ dims.nx }}; i++) ssPrintf("x_sim[%d] = %f\n", i, out_x[i]); - // ssPrintf("\n"); - -} - - -static void mdlTerminate(SimStruct *S) -{ - sim_solver_capsule *capsule = ssGetUserData(S); - - {{ model.name }}_acados_sim_free(capsule); - {{ model.name }}_acados_sim_solver_free_capsule(capsule); -} - - -#ifdef MATLAB_MEX_FILE -#include "simulink.c" -#else -#include "cg_sfun.h" -#endif diff --git a/third_party/acados/acados_template/c_templates_tera/matlab_templates/acados_solver_sfun.in.c b/third_party/acados/acados_template/c_templates_tera/matlab_templates/acados_solver_sfun.in.c deleted file mode 100644 index 3dd248037a..0000000000 --- a/third_party/acados/acados_template/c_templates_tera/matlab_templates/acados_solver_sfun.in.c +++ /dev/null @@ -1,853 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - -#define S_FUNCTION_NAME acados_solver_sfunction_{{ model.name }} -#define S_FUNCTION_LEVEL 2 - -#define MDL_START - -// acados -// #include "acados/utils/print.h" -#include "acados_c/sim_interface.h" -#include "acados_c/external_function_interface.h" - -// example specific -#include "{{ model.name }}_model/{{ model.name }}_model.h" -#include "acados_solver_{{ model.name }}.h" - -#include "simstruc.h" - -{% if simulink_opts.samplingtime == "t0" -%} -#define SAMPLINGTIME {{ solver_options.time_steps[0] }} -{%- elif simulink_opts.samplingtime == "-1" -%} -#define SAMPLINGTIME -1 -{%- else -%} - {{ throw(message = "simulink_opts.samplingtime must be '-1' or 't0', got val") }} -{%- endif %} - -static void mdlInitializeSizes (SimStruct *S) -{ - // specify the number of continuous and discrete states - ssSetNumContStates(S, 0); - ssSetNumDiscStates(S, 0); - - int N = {{ model.name | upper }}_N; - - {%- for key, val in simulink_opts.inputs -%} - {%- if val != 0 and val != 1 -%} - {{ throw(message = "simulink_opts.inputs must be 0 or 1, got val") }} - {%- endif -%} - {%- endfor -%} - - {#- compute number of input ports #} - {%- set n_inputs = 0 -%} - {%- if dims.nbx_0 > 0 and simulink_opts.inputs.lbx_0 -%} {#- lbx_0 #} - {%- set n_inputs = n_inputs + 1 -%} - {%- endif -%} - {%- if dims.nbx_0 > 0 and simulink_opts.inputs.ubx_0 -%} {#- ubx_0 #} - {%- set n_inputs = n_inputs + 1 -%} - {%- endif -%} - {%- if dims.np > 0 and simulink_opts.inputs.parameter_traj -%} {#- parameter_traj #} - {%- set n_inputs = n_inputs + 1 -%} - {%- endif -%} - {%- if dims.ny_0 > 0 and simulink_opts.inputs.y_ref_0 -%} {#- y_ref_0 -#} - {%- set n_inputs = n_inputs + 1 -%} - {%- endif -%} - {%- if dims.ny > 0 and dims.N > 1 and simulink_opts.inputs.y_ref -%} {#- y_ref -#} - {%- set n_inputs = n_inputs + 1 -%} - {%- endif -%} - {%- if dims.ny_e > 0 and dims.N > 0 and simulink_opts.inputs.y_ref_e -%} {#- y_ref_e #} - {%- set n_inputs = n_inputs + 1 -%} - {%- endif -%} - {%- if dims.nbx > 0 and dims.N > 1 and simulink_opts.inputs.lbx -%} {#- lbx #} - {%- set n_inputs = n_inputs + 1 -%} - {%- endif -%} - {%- if dims.nbx > 0 and dims.N > 1 and simulink_opts.inputs.ubx -%} {#- ubx #} - {%- set n_inputs = n_inputs + 1 -%} - {%- endif -%} - {%- if dims.nbx_e > 0 and dims.N > 0 and simulink_opts.inputs.lbx_e -%} {#- lbx_e #} - {%- set n_inputs = n_inputs + 1 -%} - {%- endif -%} - {%- if dims.nbx_e > 0 and dims.N > 0 and simulink_opts.inputs.ubx_e -%} {#- ubx_e #} - {%- set n_inputs = n_inputs + 1 -%} - {%- endif -%} - {%- if dims.nbu > 0 and dims.N > 0 and simulink_opts.inputs.lbu -%} {#- lbu #} - {%- set n_inputs = n_inputs + 1 -%} - {%- endif -%} - {%- if dims.nbu > 0 and dims.N > 0 and simulink_opts.inputs.ubu -%} {#- ubu #} - {%- set n_inputs = n_inputs + 1 -%} - {%- endif -%} - {%- if dims.ng > 0 and simulink_opts.inputs.lg -%} {#- lg #} - {%- set n_inputs = n_inputs + 1 -%} - {%- endif -%} - {%- if dims.ng > 0 and simulink_opts.inputs.ug -%} {#- ug #} - {%- set n_inputs = n_inputs + 1 -%} - {%- endif -%} - {%- if dims.nh > 0 and simulink_opts.inputs.lh -%} {#- lh #} - {%- set n_inputs = n_inputs + 1 -%} - {%- endif -%} - {%- if dims.nh > 0 and simulink_opts.inputs.uh -%} {#- uh #} - {%- set n_inputs = n_inputs + 1 -%} - {%- endif -%} - {%- if dims.nh_e > 0 and simulink_opts.inputs.lh_e -%} {#- lh_e #} - {%- set n_inputs = n_inputs + 1 -%} - {%- endif -%} - {%- if dims.nh_e > 0 and simulink_opts.inputs.uh_e -%} {#- uh_e #} - {%- set n_inputs = n_inputs + 1 -%} - {%- endif -%} - - {%- for key, val in simulink_opts.inputs -%} - {%- if val != 0 and val != 1 -%} - {{ throw(message = "simulink_opts.inputs must be 0 or 1, got val") }} - {%- endif -%} - {%- endfor -%} - {%- if dims.ny_0 > 0 and simulink_opts.inputs.cost_W_0 %} {#- cost_W_0 #} - {%- set n_inputs = n_inputs + 1 %} - {%- endif -%} - {%- if dims.ny > 0 and simulink_opts.inputs.cost_W %} {#- cost_W #} - {%- set n_inputs = n_inputs + 1 %} - {%- endif -%} - {%- if dims.ny_e > 0 and simulink_opts.inputs.cost_W_e %} {#- cost_W_e #} - {%- set n_inputs = n_inputs + 1 -%} - {%- endif -%} - - {%- if simulink_opts.inputs.reset_solver -%} {#- reset_solver #} - {%- set n_inputs = n_inputs + 1 -%} - {%- endif -%} - - {%- if simulink_opts.inputs.x_init -%} {#- x_init #} - {%- set n_inputs = n_inputs + 1 -%} - {%- endif -%} - - {%- if simulink_opts.inputs.u_init -%} {#- u_init #} - {%- set n_inputs = n_inputs + 1 -%} - {%- endif -%} - - // specify the number of input ports - if ( !ssSetNumInputPorts(S, {{ n_inputs }}) ) - return; - - // specify the number of output ports - {%- set_global n_outputs = 0 %} - {%- for key, val in simulink_opts.outputs %} - {%- if val == 1 %} - {%- set_global n_outputs = n_outputs + val %} - {%- elif val != 0 %} - {{ throw(message = "simulink_opts.outputs must be 0 or 1, got val") }} - {%- endif %} - {%- endfor %} - if ( !ssSetNumOutputPorts(S, {{ n_outputs }}) ) - return; - - // specify dimension information for the input ports - {%- set i_input = -1 %}{# note here i_input is 0-based #} - {%- if dims.nbx_0 > 0 and simulink_opts.inputs.lbx_0 -%} {#- lbx_0 #} - {%- set i_input = i_input + 1 %} - // lbx_0 - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.nbx_0 }}); - {%- endif %} - {%- if dims.nbx_0 > 0 and simulink_opts.inputs.ubx_0 -%} {#- ubx_0 #} - {%- set i_input = i_input + 1 %} - // ubx_0 - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.nbx_0 }}); - {%- endif %} - - {%- if dims.np > 0 and simulink_opts.inputs.parameter_traj -%} {#- parameter_traj #} - {%- set i_input = i_input + 1 %} - // parameters - ssSetInputPortVectorDimension(S, {{ i_input }}, (N+1) * {{ dims.np }}); - {%- endif %} - - {%- if dims.ny > 0 and simulink_opts.inputs.y_ref_0 %} - {%- set i_input = i_input + 1 %} - // y_ref_0 - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.ny_0 }}); - {%- endif %} - - {%- if dims.ny > 0 and dims.N > 1 and simulink_opts.inputs.y_ref %} - {%- set i_input = i_input + 1 %} - // y_ref - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ (dims.N-1) * dims.ny }}); - {%- endif %} - - {%- if dims.ny_e > 0 and dims.N > 0 and simulink_opts.inputs.y_ref_e %} - {%- set i_input = i_input + 1 %} - // y_ref_e - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.ny_e }}); - {%- endif %} - - {%- if dims.nbx > 0 and dims.N > 1 and simulink_opts.inputs.lbx -%} {#- lbx #} - {%- set i_input = i_input + 1 %} - // lbx - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ (dims.N-1) * dims.nbx }}); - {%- endif %} - {%- if dims.nbx > 0 and dims.N > 1 and simulink_opts.inputs.ubx -%} {#- ubx #} - {%- set i_input = i_input + 1 %} - // ubx - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ (dims.N-1) * dims.nbx }}); - {%- endif %} - - {%- if dims.nbx_e > 0 and dims.N > 0 and simulink_opts.inputs.lbx_e -%} {#- lbx_e #} - {%- set i_input = i_input + 1 %} - // lbx_e - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.nbx_e }}); - {%- endif %} - {%- if dims.nbx_e > 0 and dims.N > 0 and simulink_opts.inputs.ubx_e -%} {#- ubx_e #} - {%- set i_input = i_input + 1 %} - // ubx_e - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.nbx_e }}); - {%- endif %} - - {%- if dims.nbu > 0 and dims.N > 0 and simulink_opts.inputs.lbu -%} {#- lbu #} - {%- set i_input = i_input + 1 %} - // lbu - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.N*dims.nbu }}); - {%- endif -%} - {%- if dims.nbu > 0 and dims.N > 0 and simulink_opts.inputs.ubu -%} {#- ubu #} - {%- set i_input = i_input + 1 %} - // ubu - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.N*dims.nbu }}); - {%- endif -%} - - - {%- if dims.ng > 0 and simulink_opts.inputs.lg -%} {#- lg #} - {%- set i_input = i_input + 1 %} - // lg - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.N*dims.ng }}); - {%- endif -%} - {%- if dims.ng > 0 and simulink_opts.inputs.ug -%} {#- ug #} - {%- set i_input = i_input + 1 %} - // ug - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.N*dims.ng }}); - {%- endif -%} - - {%- if dims.nh > 0 and simulink_opts.inputs.lh -%} {#- lh #} - {%- set i_input = i_input + 1 %} - // lh - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.N*dims.nh }}); - {%- endif -%} - {%- if dims.nh > 0 and simulink_opts.inputs.uh -%} {#- uh #} - {%- set i_input = i_input + 1 %} - // uh - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.N*dims.nh }}); - {%- endif -%} - - {%- if dims.nh_e > 0 and simulink_opts.inputs.lh_e -%} {#- lh_e #} - {%- set i_input = i_input + 1 %} - // lh_e - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.nh_e }}); - {%- endif -%} - {%- if dims.nh_e > 0 and simulink_opts.inputs.uh_e -%} {#- uh_e #} - {%- set i_input = i_input + 1 %} - // uh_e - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.nh_e }}); - {%- endif -%} - - {%- if dims.ny_0 > 0 and simulink_opts.inputs.cost_W_0 %} {#- cost_W_0 #} - {%- set i_input = i_input + 1 %} - // cost_W_0 - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.ny_0 * dims.ny_0 }}); - {%- endif %} - - {%- if dims.ny > 0 and simulink_opts.inputs.cost_W %} {#- cost_W #} - {%- set i_input = i_input + 1 %} - // cost_W - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.ny * dims.ny }}); - {%- endif %} - - {%- if dims.ny_e > 0 and simulink_opts.inputs.cost_W_e %} {#- cost_W_e #} - {%- set i_input = i_input + 1 %} - // cost_W_e - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.ny_e * dims.ny_e }}); - {%- endif %} - - {%- if simulink_opts.inputs.reset_solver -%} {#- reset_solver #} - {%- set i_input = i_input + 1 %} - // reset_solver - ssSetInputPortVectorDimension(S, {{ i_input }}, 1); - {%- endif -%} - - {%- if simulink_opts.inputs.x_init -%} {#- x_init #} - {%- set i_input = i_input + 1 %} - // x_init - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.nx * (dims.N+1) }}); - {%- endif -%} - - {%- if simulink_opts.inputs.u_init -%} {#- u_init #} - {%- set i_input = i_input + 1 %} - // u_init - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.nu * (dims.N) }}); - {%- endif -%} - - /* specify dimension information for the OUTPUT ports */ - {%- set i_output = -1 %}{# note here i_output is 0-based #} - {%- if dims.nu > 0 and simulink_opts.outputs.u0 == 1 %} - {%- set i_output = i_output + 1 %} - ssSetOutputPortVectorDimension(S, {{ i_output }}, {{ dims.nu }} ); - {%- endif %} - - {%- if simulink_opts.outputs.utraj == 1 %} - {%- set i_output = i_output + 1 %} - ssSetOutputPortVectorDimension(S, {{ i_output }}, {{ dims.nu * dims.N }} ); - {%- endif %} - - {%- if simulink_opts.outputs.xtraj == 1 %} - {%- set i_output = i_output + 1 %} - ssSetOutputPortVectorDimension(S, {{ i_output }}, {{ dims.nx * (dims.N+1) }} ); - {%- endif %} - - {%- if simulink_opts.outputs.solver_status == 1 %} - {%- set i_output = i_output + 1 %} - ssSetOutputPortVectorDimension(S, {{ i_output }}, 1 ); - {%- endif %} - - {%- if simulink_opts.outputs.cost_value == 1 %} - {%- set i_output = i_output + 1 %} - ssSetOutputPortVectorDimension(S, {{ i_output }}, 1 ); - {%- endif %} - - {%- if simulink_opts.outputs.KKT_residual == 1 %} - {%- set i_output = i_output + 1 %} - ssSetOutputPortVectorDimension(S, {{ i_output }}, 1 ); - {%- endif %} - - {%- if simulink_opts.outputs.KKT_residuals == 1 %} - {%- set i_output = i_output + 1 %} - ssSetOutputPortVectorDimension(S, {{ i_output }}, 4 ); - {%- endif %} - - {%- if dims.N > 0 and simulink_opts.outputs.x1 == 1 %} - {%- set i_output = i_output + 1 %} - ssSetOutputPortVectorDimension(S, {{ i_output }}, {{ dims.nx }} ); // state at shooting node 1 - {%- endif %} - - {%- if simulink_opts.outputs.CPU_time == 1 %} - {%- set i_output = i_output + 1 %} - ssSetOutputPortVectorDimension(S, {{ i_output }}, 1); - {%- endif %} - - {%- if simulink_opts.outputs.CPU_time_sim == 1 %} - {%- set i_output = i_output + 1 %} - ssSetOutputPortVectorDimension(S, {{ i_output }}, 1); - {%- endif %} - - {%- if simulink_opts.outputs.CPU_time_qp == 1 %} - {%- set i_output = i_output + 1 %} - ssSetOutputPortVectorDimension(S, {{ i_output }}, 1); - {%- endif %} - - {%- if simulink_opts.outputs.CPU_time_lin == 1 %} - {%- set i_output = i_output + 1 %} - ssSetOutputPortVectorDimension(S, {{ i_output }}, 1); - {%- endif %} - - {%- if simulink_opts.outputs.sqp_iter == 1 %} - {%- set i_output = i_output + 1 %} - ssSetOutputPortVectorDimension(S, {{ i_output }}, 1 ); - {%- endif %} - - // specify the direct feedthrough status - // should be set to 1 for all inputs used in mdlOutputs - {%- for i in range(end=n_inputs) %} - ssSetInputPortDirectFeedThrough(S, {{ i }}, 1); - {%- endfor %} - - // one sample time - ssSetNumSampleTimes(S, 1); -} - - -#if defined(MATLAB_MEX_FILE) - -#define MDL_SET_INPUT_PORT_DIMENSION_INFO -#define MDL_SET_OUTPUT_PORT_DIMENSION_INFO - -static void mdlSetInputPortDimensionInfo(SimStruct *S, int_T port, const DimsInfo_T *dimsInfo) -{ - if ( !ssSetInputPortDimensionInfo(S, port, dimsInfo) ) - return; -} - -static void mdlSetOutputPortDimensionInfo(SimStruct *S, int_T port, const DimsInfo_T *dimsInfo) -{ - if ( !ssSetOutputPortDimensionInfo(S, port, dimsInfo) ) - return; -} - -#endif /* MATLAB_MEX_FILE */ - - -static void mdlInitializeSampleTimes(SimStruct *S) -{ - ssSetSampleTime(S, 0, SAMPLINGTIME); - ssSetOffsetTime(S, 0, 0.0); -} - - -static void mdlStart(SimStruct *S) -{ - {{ model.name }}_solver_capsule *capsule = {{ model.name }}_acados_create_capsule(); - {{ model.name }}_acados_create(capsule); - - ssSetUserData(S, (void*)capsule); -} - - -static void mdlOutputs(SimStruct *S, int_T tid) -{ - {{ model.name }}_solver_capsule *capsule = ssGetUserData(S); - ocp_nlp_config *nlp_config = {{ model.name }}_acados_get_nlp_config(capsule); - ocp_nlp_dims *nlp_dims = {{ model.name }}_acados_get_nlp_dims(capsule); - ocp_nlp_in *nlp_in = {{ model.name }}_acados_get_nlp_in(capsule); - ocp_nlp_out *nlp_out = {{ model.name }}_acados_get_nlp_out(capsule); - - InputRealPtrsType in_sign; - - int N = {{ model.name | upper }}_N; - - {%- set buffer_sizes = [dims.nbx_0, dims.np, dims.nbx, dims.nbx_e, dims.nbu, dims.ng, dims.nh, dims.ng_e, dims.nh_e] -%} - - {%- if dims.ny_0 > 0 and simulink_opts.inputs.y_ref_0 %} {# y_ref_0 #} - {%- set buffer_sizes = buffer_sizes | concat(with=(dims.ny_0)) %} - {%- endif %} - {%- if dims.ny > 0 and dims.N > 1 and simulink_opts.inputs.y_ref %} {# y_ref #} - {%- set buffer_sizes = buffer_sizes | concat(with=(dims.ny)) %} - {%- endif %} - {%- if dims.ny_e > 0 and dims.N > 0 and simulink_opts.inputs.y_ref_e %} {# y_ref_e #} - {%- set buffer_sizes = buffer_sizes | concat(with=(dims.ny_e)) %} - {%- endif %} - - {%- if dims.ny_0 > 0 and simulink_opts.inputs.cost_W_0 %} {#- cost_W_0 #} - {%- set buffer_sizes = buffer_sizes | concat(with=(dims.ny_0 * dims.ny_0)) %} - {%- endif %} - {%- if dims.ny > 0 and simulink_opts.inputs.cost_W %} {#- cost_W #} - {%- set buffer_sizes = buffer_sizes | concat(with=(dims.ny * dims.ny)) %} - {%- endif %} - {%- if dims.ny_e > 0 and simulink_opts.inputs.cost_W_e %} {#- cost_W_e #} - {%- set buffer_sizes = buffer_sizes | concat(with=(dims.ny_e * dims.ny_e)) %} - {%- endif %} - - // local buffer - {%- set buffer_size = buffer_sizes | sort | last %} - real_t buffer[{{ buffer_size }}]; - - /* go through inputs */ - {%- set i_input = -1 %} - {%- if dims.nbx_0 > 0 and simulink_opts.inputs.lbx_0 -%} {#- lbx_0 #} - // lbx_0 - {%- set i_input = i_input + 1 %} - in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - for (int i = 0; i < {{ dims.nbx_0 }}; i++) - buffer[i] = (double)(*in_sign[i]); - - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "lbx", buffer); - {%- endif %} - - {%- if dims.nbx_0 > 0 and simulink_opts.inputs.ubx_0 -%} {#- ubx_0 #} - // ubx_0 - {%- set i_input = i_input + 1 %} - in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - for (int i = 0; i < {{ dims.nbx_0 }}; i++) - buffer[i] = (double)(*in_sign[i]); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "ubx", buffer); - {%- endif %} - - {%- if dims.np > 0 and simulink_opts.inputs.parameter_traj -%} {#- parameter_traj #} - // parameters - stage-variant !!! - {%- set i_input = i_input + 1 %} - in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - - // update value of parameters - for (int ii = 0; ii <= N; ii++) - { - for (int jj = 0; jj < {{ dims.np }}; jj++) - buffer[jj] = (double)(*in_sign[ii*{{dims.np}}+jj]); - {{ model.name }}_acados_update_params(capsule, ii, buffer, {{ dims.np }}); - } - {%- endif %} - - {% if dims.ny_0 > 0 and simulink_opts.inputs.y_ref_0 %} - // y_ref_0 - {%- set i_input = i_input + 1 %} - in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - - for (int i = 0; i < {{ dims.ny_0 }}; i++) - buffer[i] = (double)(*in_sign[i]); - - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "yref", (void *) buffer); - {%- endif %} - - {% if dims.ny > 0 and dims.N > 1 and simulink_opts.inputs.y_ref %} - // y_ref - for stages 1 to N-1 - {%- set i_input = i_input + 1 %} - in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - - for (int ii = 1; ii < N; ii++) - { - for (int jj = 0; jj < {{ dims.ny }}; jj++) - buffer[jj] = (double)(*in_sign[(ii-1)*{{ dims.ny }}+jj]); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, ii, "yref", (void *) buffer); - } - {%- endif %} - - {% if dims.ny_e > 0 and dims.N > 0 and simulink_opts.inputs.y_ref_e %} - // y_ref_e - {%- set i_input = i_input + 1 %} - in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - - for (int i = 0; i < {{ dims.ny_e }}; i++) - buffer[i] = (double)(*in_sign[i]); - - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "yref", (void *) buffer); - {%- endif %} - - {%- if dims.nbx > 0 and dims.N > 1 and simulink_opts.inputs.lbx -%} {#- lbx #} - // lbx - {%- set i_input = i_input + 1 %} - in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - for (int ii = 1; ii < N; ii++) - { - for (int jj = 0; jj < {{ dims.nbx }}; jj++) - buffer[jj] = (double)(*in_sign[(ii-1)*{{ dims.nbx }}+jj]); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "lbx", (void *) buffer); - } - {%- endif %} - {%- if dims.nbx > 0 and dims.N > 1 and simulink_opts.inputs.ubx -%} {#- ubx #} - // ubx - {%- set i_input = i_input + 1 %} - in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - for (int ii = 1; ii < N; ii++) - { - for (int jj = 0; jj < {{ dims.nbx }}; jj++) - buffer[jj] = (double)(*in_sign[(ii-1)*{{ dims.nbx }}+jj]); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "ubx", (void *) buffer); - } - {%- endif %} - - - {%- if dims.nbx_e > 0 and dims.N > 0 and simulink_opts.inputs.lbx_e -%} {#- lbx_e #} - // lbx_e - {%- set i_input = i_input + 1 %} - in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - - for (int i = 0; i < {{ dims.nbx_e }}; i++) - buffer[i] = (double)(*in_sign[i]); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "lbx", buffer); - {%- endif %} - {%- if dims.nbx_e > 0 and dims.N > 0 and simulink_opts.inputs.ubx_e -%} {#- ubx_e #} - // ubx_e - {%- set i_input = i_input + 1 %} - in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - - for (int i = 0; i < {{ dims.nbx_e }}; i++) - buffer[i] = (double)(*in_sign[i]); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "ubx", buffer); - {%- endif %} - - - {%- if dims.nbu > 0 and dims.N > 0 and simulink_opts.inputs.lbu -%} {#- lbu #} - // lbu - {%- set i_input = i_input + 1 %} - in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - for (int ii = 0; ii < N; ii++) - { - for (int jj = 0; jj < {{ dims.nbu }}; jj++) - buffer[jj] = (double)(*in_sign[ii*{{ dims.nbu }}+jj]); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "lbu", (void *) buffer); - } - {%- endif -%} - {%- if dims.nbu > 0 and dims.N > 0 and simulink_opts.inputs.ubu -%} {#- ubu #} - // ubu - {%- set i_input = i_input + 1 %} - in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - for (int ii = 0; ii < N; ii++) - { - for (int jj = 0; jj < {{ dims.nbu }}; jj++) - buffer[jj] = (double)(*in_sign[ii*{{ dims.nbu }}+jj]); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "ubu", (void *) buffer); - } - {%- endif -%} - - {%- if dims.ng > 0 and simulink_opts.inputs.lg -%} {#- lg #} - // lg - {%- set i_input = i_input + 1 %} - in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - - for (int ii = 0; ii < N; ii++) - { - for (int jj = 0; jj < {{ dims.ng }}; jj++) - buffer[jj] = (double)(*in_sign[ii*{{ dims.ng }}+jj]); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "lg", (void *) buffer); - } - {%- endif -%} - {%- if dims.ng > 0 and simulink_opts.inputs.ug -%} {#- ug #} - // ug - {%- set i_input = i_input + 1 %} - in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - - for (int ii = 0; ii < N; ii++) - { - for (int jj = 0; jj < {{ dims.ng }}; jj++) - buffer[jj] = (double)(*in_sign[ii*{{ dims.ng }}+jj]); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "ug", (void *) buffer); - } - {%- endif -%} - - {%- if dims.nh > 0 and simulink_opts.inputs.lh -%} {#- lh #} - // lh - {%- set i_input = i_input + 1 %} - in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - - for (int ii = 0; ii < N; ii++) - { - for (int jj = 0; jj < {{ dims.nh }}; jj++) - buffer[jj] = (double)(*in_sign[ii*{{ dims.nh }}+jj]); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "lh", (void *) buffer); - } - {%- endif -%} - {%- if dims.nh > 0 and simulink_opts.inputs.uh -%} {#- uh #} - // uh - {%- set i_input = i_input + 1 %} - in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - - for (int ii = 0; ii < N; ii++) - { - for (int jj = 0; jj < {{ dims.nh }}; jj++) - buffer[jj] = (double)(*in_sign[ii*{{ dims.nh }}+jj]); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "uh", (void *) buffer); - } - {%- endif -%} - - - {%- if dims.nh_e > 0 and simulink_opts.inputs.lh_e -%} {#- lh_e #} - // lh_e - {%- set i_input = i_input + 1 %} - in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - for (int i = 0; i < {{ dims.nh_e }}; i++) - buffer[i] = (double)(*in_sign[i]); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "lh", buffer); - {%- endif -%} - {%- if dims.nh_e > 0 and simulink_opts.inputs.uh_e -%} {#- uh_e #} - // uh_e - {%- set i_input = i_input + 1 %} - in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - for (int i = 0; i < {{ dims.nh_e }}; i++) - buffer[i] = (double)(*in_sign[i]); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "uh", buffer); - {%- endif -%} - - {%- if dims.ny_0 > 0 and simulink_opts.inputs.cost_W_0 %} {#- cost_W_0 #} - // cost_W_0 - {%- set i_input = i_input + 1 %} - in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - for (int i = 0; i < {{ dims.ny_0 * dims.ny_0 }}; i++) - buffer[i] = (double)(*in_sign[i]); - - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "W", buffer); - {%- endif %} - - {%- if dims.ny > 0 and simulink_opts.inputs.cost_W %} {#- cost_W #} - // cost_W - {%- set i_input = i_input + 1 %} - in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - for (int i = 0; i < {{ dims.ny * dims.ny }}; i++) - buffer[i] = (double)(*in_sign[i]); - - for (int ii = 1; ii < N; ii++) - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, ii, "W", buffer); - {%- endif %} - - {%- if dims.ny_e > 0 and simulink_opts.inputs.cost_W_e %} {#- cost_W_e #} - // cost_W_e - {%- set i_input = i_input + 1 %} - in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - for (int i = 0; i < {{ dims.ny_e * dims.ny_e }}; i++) - buffer[i] = (double)(*in_sign[i]); - - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "W", buffer); - {%- endif %} - - {%- if simulink_opts.inputs.reset_solver %} {#- reset_solver #} - // reset_solver - {%- set i_input = i_input + 1 %} - in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - double reset = (double)(*in_sign[0]); - if (reset) - { - {{ model.name }}_acados_reset(capsule, 1); - } - {%- endif %} - - {%- if simulink_opts.inputs.x_init %} {#- x_init #} - // x_init - {%- set i_input = i_input + 1 %} - in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - for (int ii = 0; ii < {{ dims.N + 1 }}; ii++) - { - for (int jj = 0; jj < {{ dims.nx }}; jj++) - buffer[jj] = (double)(*in_sign[(ii)*{{ dims.nx }}+jj]); - ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, ii, "x", (void *) buffer); - } - {%- endif %} - - {%- if simulink_opts.inputs.u_init %} {#- u_init #} - // u_init - {%- set i_input = i_input + 1 %} - in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - for (int ii = 0; ii < N; ii++) - { - for (int jj = 0; jj < {{ dims.nu }}; jj++) - buffer[jj] = (double)(*in_sign[(ii)*{{ dims.nu }}+jj]); - ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, ii, "u", (void *) buffer); - } - {%- endif %} - - /* call solver */ - int rti_phase = 0; - ocp_nlp_solver_opts_set(nlp_config, capsule->nlp_opts, "rti_phase", &rti_phase); - int acados_status = {{ model.name }}_acados_solve(capsule); - - - /* set outputs */ - // assign pointers to output signals - real_t *out_u0, *out_utraj, *out_xtraj, *out_status, *out_sqp_iter, *out_KKT_res, *out_KKT_residuals, *out_x1, *out_cpu_time, *out_cpu_time_sim, *out_cpu_time_qp, *out_cpu_time_lin, *out_cost_value; - int tmp_int; - - {%- set i_output = -1 -%}{# note here i_output is 0-based #} - {%- if dims.nu > 0 and simulink_opts.outputs.u0 == 1 %} - {%- set i_output = i_output + 1 %} - out_u0 = ssGetOutputPortRealSignal(S, {{ i_output }}); - ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, 0, "u", (void *) out_u0); - {%- endif %} - - {%- if simulink_opts.outputs.utraj == 1 %} - {%- set i_output = i_output + 1 %} - out_utraj = ssGetOutputPortRealSignal(S, {{ i_output }}); - for (int ii = 0; ii < N; ii++) - ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, ii, - "u", (void *) (out_utraj + ii * {{ dims.nu }})); - {%- endif %} - - {% if simulink_opts.outputs.xtraj == 1 %} - {%- set i_output = i_output + 1 %} - - out_xtraj = ssGetOutputPortRealSignal(S, {{ i_output }}); - for (int ii = 0; ii < {{ dims.N + 1 }}; ii++) - ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, ii, - "x", (void *) (out_xtraj + ii * {{ dims.nx }})); - {%- endif %} - - {%- if simulink_opts.outputs.solver_status == 1 %} - {%- set i_output = i_output + 1 %} - out_status = ssGetOutputPortRealSignal(S, {{ i_output }}); - *out_status = (real_t) acados_status; - {%- endif %} - - {%- if simulink_opts.outputs.cost_value == 1 %} - {%- set i_output = i_output + 1 %} - out_cost_value = ssGetOutputPortRealSignal(S, {{ i_output }}); - ocp_nlp_eval_cost(capsule->nlp_solver, nlp_in, nlp_out); - ocp_nlp_get(nlp_config, capsule->nlp_solver, "cost_value", (void *) out_cost_value); - {%- endif %} - - {%- if simulink_opts.outputs.KKT_residual == 1 %} - {%- set i_output = i_output + 1 %} - out_KKT_res = ssGetOutputPortRealSignal(S, {{ i_output }}); - *out_KKT_res = (real_t) nlp_out->inf_norm_res; - {%- endif %} - - {%- if simulink_opts.outputs.KKT_residuals == 1 %} - {%- set i_output = i_output + 1 %} - out_KKT_residuals = ssGetOutputPortRealSignal(S, {{ i_output }}); - - {%- if solver_options.nlp_solver_type == "SQP_RTI" %} - ocp_nlp_eval_residuals(capsule->nlp_solver, nlp_in, nlp_out); - {%- endif %} - ocp_nlp_get(nlp_config, capsule->nlp_solver, "res_stat", (void *) &out_KKT_residuals[0]); - ocp_nlp_get(nlp_config, capsule->nlp_solver, "res_eq", (void *) &out_KKT_residuals[1]); - ocp_nlp_get(nlp_config, capsule->nlp_solver, "res_ineq", (void *) &out_KKT_residuals[2]); - ocp_nlp_get(nlp_config, capsule->nlp_solver, "res_comp", (void *) &out_KKT_residuals[3]); - {%- endif %} - - {%- if dims.N > 0 and simulink_opts.outputs.x1 == 1 %} - {%- set i_output = i_output + 1 %} - out_x1 = ssGetOutputPortRealSignal(S, {{ i_output }}); - ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, 1, "x", (void *) out_x1); - {%- endif %} - - {%- if simulink_opts.outputs.CPU_time == 1 %} - {%- set i_output = i_output + 1 %} - out_cpu_time = ssGetOutputPortRealSignal(S, {{ i_output }}); - // get solution time - ocp_nlp_get(nlp_config, capsule->nlp_solver, "time_tot", (void *) out_cpu_time); - {%- endif -%} - - {%- if simulink_opts.outputs.CPU_time_sim == 1 %} - {%- set i_output = i_output + 1 %} - out_cpu_time_sim = ssGetOutputPortRealSignal(S, {{ i_output }}); - ocp_nlp_get(nlp_config, capsule->nlp_solver, "time_sim", (void *) out_cpu_time_sim); - {%- endif -%} - - {%- if simulink_opts.outputs.CPU_time_qp == 1 %} - {%- set i_output = i_output + 1 %} - out_cpu_time_qp = ssGetOutputPortRealSignal(S, {{ i_output }}); - ocp_nlp_get(nlp_config, capsule->nlp_solver, "time_qp", (void *) out_cpu_time_qp); - {%- endif -%} - - {%- if simulink_opts.outputs.CPU_time_lin == 1 %} - {%- set i_output = i_output + 1 %} - out_cpu_time_lin = ssGetOutputPortRealSignal(S, {{ i_output }}); - ocp_nlp_get(nlp_config, capsule->nlp_solver, "time_lin", (void *) out_cpu_time_lin); - {%- endif -%} - - {%- if simulink_opts.outputs.sqp_iter == 1 %} - {%- set i_output = i_output + 1 %} - out_sqp_iter = ssGetOutputPortRealSignal(S, {{ i_output }}); - // get sqp iter - ocp_nlp_get(nlp_config, capsule->nlp_solver, "sqp_iter", (void *) &tmp_int); - *out_sqp_iter = (real_t) tmp_int; - {%- endif %} - -} - -static void mdlTerminate(SimStruct *S) -{ - {{ model.name }}_solver_capsule *capsule = ssGetUserData(S); - - {{ model.name }}_acados_free(capsule); - {{ model.name }}_acados_free_capsule(capsule); -} - - -#ifdef MATLAB_MEX_FILE -#include "simulink.c" -#else -#include "cg_sfun.h" -#endif diff --git a/third_party/acados/acados_template/c_templates_tera/matlab_templates/main_mex.in.c b/third_party/acados/acados_template/c_templates_tera/matlab_templates/main_mex.in.c deleted file mode 100644 index 851a3cc04f..0000000000 --- a/third_party/acados/acados_template/c_templates_tera/matlab_templates/main_mex.in.c +++ /dev/null @@ -1,181 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -// standard -#include -#include -// acados -#include "acados/utils/print.h" -#include "acados/utils/math.h" -#include "acados_c/ocp_nlp_interface.h" -#include "acados_solver_{{ model.name }}.h" -// mex -#include "mex.h" - -/* auxilary mex */ -// prints a matrix in column-major format (exponential notation) -void MEX_print_exp_mat(int m, int n, double *A, int lda) -{ - for (int i=0; iN; i++) - { - ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "x", x_init); - ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "u", u0); - } - status = {{ model.name }}_acados_solve(); - ocp_nlp_get(nlp_config, nlp_solver, "time_tot", &elapsed_time); - min_time = MIN(elapsed_time, min_time); - } - - /* print solution and statistics */ - for (int ii = 0; ii <= nlp_dims->N; ii++) - ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, ii, "x", &xtraj[ii*{{ dims.nx }}]); - for (int ii = 0; ii < nlp_dims->N; ii++) - ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, ii, "u", &utraj[ii*{{ dims.nu }}]); - - mexPrintf("\n--- xtraj ---\n"); - MEX_print_exp_tran_mat( {{ dims.nx }}, {{ dims.N }}+1, xtraj, {{ dims.nx }} ); - mexPrintf("\n--- utraj ---\n"); - MEX_print_exp_tran_mat( {{ dims.nu }}, {{ dims.N }}, utraj, {{ dims.nu }} ); - - mexPrintf("\nsolved ocp %d times, solution printed above\n\n", NTIMINGS); - - if (status == ACADOS_SUCCESS) - mexPrintf("{{ model.name }}_acados_solve(): SUCCESS!\n"); - else - mexPrintf("{{ model.name }}_acados_solve() failed with status %d.\n", status); - - // get solution - ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, 0, "kkt_norm_inf", &kkt_norm_inf); - ocp_nlp_get(nlp_config, nlp_solver, "sqp_iter", &sqp_iter); - - mexPrintf("\nSolver info:\n"); - mexPrintf(" SQP iterations %2d\n minimum time for 1 solve %f [ms]\n KKT %e\n", - sqp_iter, min_time*1000, kkt_norm_inf); - - // free solver - status = {{ model.name }}_acados_free(); - if (status) - { - mexPrintf("{{ model.name }}_acados_free() returned status %d.\n", status); - } - - return; -} diff --git a/third_party/acados/acados_template/c_templates_tera/matlab_templates/make_main_mex.in.m b/third_party/acados/acados_template/c_templates_tera/matlab_templates/make_main_mex.in.m deleted file mode 100644 index d217948456..0000000000 --- a/third_party/acados/acados_template/c_templates_tera/matlab_templates/make_main_mex.in.m +++ /dev/null @@ -1,103 +0,0 @@ -% -% Copyright (c) The acados authors. -% -% This file is part of acados. -% -% The 2-Clause BSD License -% -% Redistribution and use in source and binary forms, with or without -% modification, are permitted provided that the following conditions are met: -% -% 1. Redistributions of source code must retain the above copyright notice, -% this list of conditions and the following disclaimer. -% -% 2. Redistributions in binary form must reproduce the above copyright notice, -% this list of conditions and the following disclaimer in the documentation -% and/or other materials provided with the distribution. -% -% THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -% AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -% IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -% ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -% LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -% CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -% SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -% INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -% CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -% ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -% POSSIBILITY OF SUCH DAMAGE.; - -% - -function make_main_mex_{{ model.name }}() - - opts.output_dir = pwd; - - % get acados folder - acados_folder = getenv('ACADOS_INSTALL_DIR'); - - % set paths - acados_include = ['-I' fullfile(acados_folder, 'include')]; - template_lib_include = ['-l' 'acados_solver_{{ model.name }}']; - template_lib_path = ['-L' fullfile(pwd)]; - - acados_lib_path = ['-L' fullfile(acados_folder, 'lib')]; - external_include = ['-I', fullfile(acados_folder, 'external')]; - blasfeo_include = ['-I', fullfile(acados_folder, 'external', 'blasfeo', 'include')]; - hpipm_include = ['-I', fullfile(acados_folder, 'external', 'hpipm', 'include')]; - - mex_names = { ... - 'main_mex_{{ model.name }}' ... - }; - - mex_files = cell(length(mex_names), 1); - for k=1:length(mex_names) - mex_files{k} = fullfile([mex_names{k}, '.c']); - end - - %% octave C flags - if is_octave() - if ~exist(fullfile(opts.output_dir, 'cflags_octave.txt'), 'file') - diary(fullfile(opts.output_dir, 'cflags_octave.txt')); - diary on - mkoctfile -p CFLAGS - diary off - input_file = fopen(fullfile(opts.output_dir, 'cflags_octave.txt'), 'r'); - cflags_tmp = fscanf(input_file, '%[^\n]s'); - fclose(input_file); - if ~ismac() - cflags_tmp = [cflags_tmp, ' -std=c99 -fopenmp']; - else - cflags_tmp = [cflags_tmp, ' -std=c99']; - end - input_file = fopen(fullfile(opts.output_dir, 'cflags_octave.txt'), 'w'); - fprintf(input_file, '%s', cflags_tmp); - fclose(input_file); - end - % read cflags from file - input_file = fopen(fullfile(opts.output_dir, 'cflags_octave.txt'), 'r'); - cflags_tmp = fscanf(input_file, '%[^\n]s'); - fclose(input_file); - setenv('CFLAGS', cflags_tmp); - end - - %% compile mex - for ii=1:length(mex_files) - disp(['compiling ', mex_files{ii}]) - if is_octave() - % mkoctfile -p CFLAGS - mex(acados_include, template_lib_include, external_include, blasfeo_include, hpipm_include,... - acados_lib_path, template_lib_path, '-lacados', '-lhpipm', '-lblasfeo', mex_files{ii}) - else - if ismac() - FLAGS = 'CFLAGS=$CFLAGS -std=c99'; - else - FLAGS = 'CFLAGS=$CFLAGS -std=c99 -fopenmp'; - end - mex(FLAGS, acados_include, template_lib_include, external_include, blasfeo_include, hpipm_include,... - acados_lib_path, template_lib_path, '-lacados', '-lhpipm', '-lblasfeo', mex_files{ii}) - end - end - - -end \ No newline at end of file diff --git a/third_party/acados/acados_template/c_templates_tera/matlab_templates/make_mex.in.m b/third_party/acados/acados_template/c_templates_tera/matlab_templates/make_mex.in.m deleted file mode 100644 index 5e35827137..0000000000 --- a/third_party/acados/acados_template/c_templates_tera/matlab_templates/make_mex.in.m +++ /dev/null @@ -1,127 +0,0 @@ -% -% Copyright (c) The acados authors. -% -% This file is part of acados. -% -% The 2-Clause BSD License -% -% Redistribution and use in source and binary forms, with or without -% modification, are permitted provided that the following conditions are met: -% -% 1. Redistributions of source code must retain the above copyright notice, -% this list of conditions and the following disclaimer. -% -% 2. Redistributions in binary form must reproduce the above copyright notice, -% this list of conditions and the following disclaimer in the documentation -% and/or other materials provided with the distribution. -% -% THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -% AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -% IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -% ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -% LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -% CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -% SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -% INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -% CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -% ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -% POSSIBILITY OF SUCH DAMAGE.; - -% - -function make_mex_{{ model.name }}() - - opts.output_dir = pwd; - - % get acados folder - acados_folder = getenv('ACADOS_INSTALL_DIR'); - - % set paths - acados_include = ['-I' fullfile(acados_folder, 'include')]; - template_lib_include = ['-l' 'acados_ocp_solver_{{ model.name }}']; - template_lib_path = ['-L' fullfile(pwd)]; - - acados_lib_path = ['-L' fullfile(acados_folder, 'lib')]; - external_include = ['-I', fullfile(acados_folder, 'external')]; - blasfeo_include = ['-I', fullfile(acados_folder, 'external', 'blasfeo', 'include')]; - hpipm_include = ['-I', fullfile(acados_folder, 'external', 'hpipm', 'include')]; - - % load linking information of compiled acados - link_libs_core_filename = fullfile(acados_folder, 'lib', 'link_libs.json'); - addpath(fullfile(acados_folder, 'external', 'jsonlab')); - link_libs = loadjson(link_libs_core_filename); - - % add necessary link instructs - acados_lib_extra = {}; - lib_names = fieldnames(link_libs); - for idx = 1 : numel(lib_names) - lib_name = lib_names{idx}; - link_arg = link_libs.(lib_name); - if ~isempty(link_arg) - acados_lib_extra = [acados_lib_extra, link_arg]; - end - end - - - mex_include = ['-I', fullfile(acados_folder, 'interfaces', 'acados_matlab_octave')]; - - mex_names = { ... - 'acados_mex_create_{{ model.name }}' ... - 'acados_mex_free_{{ model.name }}' ... - 'acados_mex_solve_{{ model.name }}' ... - 'acados_mex_set_{{ model.name }}' ... - }; - - mex_files = cell(length(mex_names), 1); - for k=1:length(mex_names) - mex_files{k} = fullfile([mex_names{k}, '.c']); - end - - %% octave C flags - if is_octave() - if ~exist(fullfile(opts.output_dir, 'cflags_octave.txt'), 'file') - diary(fullfile(opts.output_dir, 'cflags_octave.txt')); - diary on - mkoctfile -p CFLAGS - diary off - input_file = fopen(fullfile(opts.output_dir, 'cflags_octave.txt'), 'r'); - cflags_tmp = fscanf(input_file, '%[^\n]s'); - fclose(input_file); - if ~ismac() - cflags_tmp = [cflags_tmp, ' -std=c99 -fopenmp']; - else - cflags_tmp = [cflags_tmp, ' -std=c99']; - end - input_file = fopen(fullfile(opts.output_dir, 'cflags_octave.txt'), 'w'); - fprintf(input_file, '%s', cflags_tmp); - fclose(input_file); - end - % read cflags from file - input_file = fopen(fullfile(opts.output_dir, 'cflags_octave.txt'), 'r'); - cflags_tmp = fscanf(input_file, '%[^\n]s'); - fclose(input_file); - setenv('CFLAGS', cflags_tmp); - end - - %% compile mex - for ii=1:length(mex_files) - disp(['compiling ', mex_files{ii}]) - if is_octave() - % mkoctfile -p CFLAGS - mex(acados_include, template_lib_include, external_include, blasfeo_include, hpipm_include,... - template_lib_path, mex_include, acados_lib_path, '-lacados', '-lhpipm', '-lblasfeo',... - acados_lib_extra{:}, mex_files{ii}) - else - if ismac() - FLAGS = 'CFLAGS=$CFLAGS -std=c99'; - else - FLAGS = 'CFLAGS=$CFLAGS -std=c99 -fopenmp'; - end - mex(FLAGS, acados_include, template_lib_include, external_include, blasfeo_include, hpipm_include,... - template_lib_path, mex_include, acados_lib_path, '-lacados', '-lhpipm', '-lblasfeo',... - acados_lib_extra{:}, mex_files{ii}) - end - end - - -end \ No newline at end of file diff --git a/third_party/acados/acados_template/c_templates_tera/matlab_templates/make_sfun.in.m b/third_party/acados/acados_template/c_templates_tera/matlab_templates/make_sfun.in.m deleted file mode 100644 index 5d74c523f8..0000000000 --- a/third_party/acados/acados_template/c_templates_tera/matlab_templates/make_sfun.in.m +++ /dev/null @@ -1,432 +0,0 @@ -% -% Copyright (c) The acados authors. -% -% This file is part of acados. -% -% The 2-Clause BSD License -% -% Redistribution and use in source and binary forms, with or without -% modification, are permitted provided that the following conditions are met: -% -% 1. Redistributions of source code must retain the above copyright notice, -% this list of conditions and the following disclaimer. -% -% 2. Redistributions in binary form must reproduce the above copyright notice, -% this list of conditions and the following disclaimer in the documentation -% and/or other materials provided with the distribution. -% -% THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -% AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -% IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -% ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -% LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -% CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -% SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -% INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -% CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -% ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -% POSSIBILITY OF SUCH DAMAGE.; - -% - -SOURCES = { ... - {%- if solver_options.integrator_type == 'ERK' %} - '{{ model.name }}_model/{{ model.name }}_expl_ode_fun.c', ... - '{{ model.name }}_model/{{ model.name }}_expl_vde_forw.c',... - {%- if solver_options.hessian_approx == 'EXACT' %} - '{{ model.name }}_model/{{ model.name }}_expl_ode_hess.c',... - {%- endif %} - {%- elif solver_options.integrator_type == "IRK" %} - '{{ model.name }}_model/{{ model.name }}_impl_dae_fun.c', ... - '{{ model.name }}_model/{{ model.name }}_impl_dae_fun_jac_x_xdot_z.c', ... - '{{ model.name }}_model/{{ model.name }}_impl_dae_jac_x_xdot_u_z.c', ... - {%- if solver_options.hessian_approx == 'EXACT' %} - '{{ model.name }}_model/{{ model.name }}_impl_dae_hess.c',... - {%- endif %} - {%- elif solver_options.integrator_type == "GNSF" %} - {% if model.gnsf.purely_linear != 1 %} - '{{ model.name }}_model/{{ model.name }}_gnsf_phi_fun.c',... - '{{ model.name }}_model/{{ model.name }}_gnsf_phi_fun_jac_y.c',... - '{{ model.name }}_model/{{ model.name }}_gnsf_phi_jac_y_uhat.c',... - {% if model.gnsf.nontrivial_f_LO == 1 %} - '{{ model.name }}_model/{{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz.c',... - {%- endif %} - {%- endif %} - '{{ model.name }}_model/{{ model.name }}_gnsf_get_matrices_fun.c',... - {%- elif solver_options.integrator_type == "DISCRETE" %} - '{{ model.name }}_model/{{ model.name }}_dyn_disc_phi_fun.c',... - '{{ model.name }}_model/{{ model.name }}_dyn_disc_phi_fun_jac.c',... - {%- if solver_options.hessian_approx == "EXACT" %} - '{{ model.name }}_model/{{ model.name }}_dyn_disc_phi_fun_jac_hess.c',... - {%- endif %} - {%- endif %} - {%- if cost.cost_type_0 == "NONLINEAR_LS" %} - '{{ model.name }}_cost/{{ model.name }}_cost_y_0_fun.c',... - '{{ model.name }}_cost/{{ model.name }}_cost_y_0_fun_jac_ut_xt.c',... - '{{ model.name }}_cost/{{ model.name }}_cost_y_0_hess.c',... - {%- elif cost.cost_type_0 == "EXTERNAL" %} - '{{ model.name }}_cost/{{ model.name }}_cost_ext_cost_0_fun.c',... - '{{ model.name }}_cost/{{ model.name }}_cost_ext_cost_0_fun_jac.c',... - '{{ model.name }}_cost/{{ model.name }}_cost_ext_cost_0_fun_jac_hess.c',... - {%- endif %} - - {%- if cost.cost_type == "NONLINEAR_LS" %} - '{{ model.name }}_cost/{{ model.name }}_cost_y_fun.c',... - '{{ model.name }}_cost/{{ model.name }}_cost_y_fun_jac_ut_xt.c',... - '{{ model.name }}_cost/{{ model.name }}_cost_y_hess.c',... - {%- elif cost.cost_type == "EXTERNAL" %} - '{{ model.name }}_cost/{{ model.name }}_cost_ext_cost_fun.c',... - '{{ model.name }}_cost/{{ model.name }}_cost_ext_cost_fun_jac.c',... - '{{ model.name }}_cost/{{ model.name }}_cost_ext_cost_fun_jac_hess.c',... - {%- endif %} - {%- if cost.cost_type_e == "NONLINEAR_LS" %} - '{{ model.name }}_cost/{{ model.name }}_cost_y_e_fun.c',... - '{{ model.name }}_cost/{{ model.name }}_cost_y_e_fun_jac_ut_xt.c',... - '{{ model.name }}_cost/{{ model.name }}_cost_y_e_hess.c',... - {%- elif cost.cost_type_e == "EXTERNAL" %} - '{{ model.name }}_cost/{{ model.name }}_cost_ext_cost_e_fun.c',... - '{{ model.name }}_cost/{{ model.name }}_cost_ext_cost_e_fun_jac.c',... - '{{ model.name }}_cost/{{ model.name }}_cost_ext_cost_e_fun_jac_hess.c',... - {%- endif %} - {%- if constraints.constr_type == "BGH" and dims.nh > 0 %} - '{{ model.name }}_constraints/{{ model.name }}_constr_h_fun.c', ... - '{{ model.name }}_constraints/{{ model.name }}_constr_h_fun_jac_uxt_zt_hess.c', ... - '{{ model.name }}_constraints/{{ model.name }}_constr_h_fun_jac_uxt_zt.c', ... - {%- elif constraints.constr_type == "BGP" and dims.nphi > 0 %} - '{{ model.name }}_constraints/{{ model.name }}_phi_constraint.c', ... - {%- endif %} - {%- if constraints.constr_type_e == "BGH" and dims.nh_e > 0 %} - '{{ model.name }}_constraints/{{ model.name }}_constr_h_e_fun.c', ... - '{{ model.name }}_constraints/{{ model.name }}_constr_h_e_fun_jac_uxt_zt_hess.c', ... - '{{ model.name }}_constraints/{{ model.name }}_constr_h_e_fun_jac_uxt_zt.c', ... - {%- elif constraints.constr_type_e == "BGP" and dims.nphi_e > 0 %} - '{{ model.name }}_constraints/{{ model.name }}_phi_e_constraint.c', ... - {%- endif %} - 'acados_solver_sfunction_{{ model.name }}.c', ... - 'acados_solver_{{ model.name }}.c' - }; - -INC_PATH = '{{ acados_include_path }}'; - -INCS = {['-I', fullfile(INC_PATH, 'blasfeo', 'include')], ... - ['-I', fullfile(INC_PATH, 'hpipm', 'include')], ... - ['-I', fullfile(INC_PATH, 'acados')], ... - ['-I', fullfile(INC_PATH)]}; - -{% if solver_options.qp_solver is containing("QPOASES") %} -INCS{end+1} = ['-I', fullfile(INC_PATH, 'qpOASES_e')]; -{% endif %} - -CFLAGS = 'CFLAGS=$CFLAGS'; -LDFLAGS = 'LDFLAGS=$LDFLAGS'; -COMPFLAGS = 'COMPFLAGS=$COMPFLAGS'; -COMPDEFINES = 'COMPDEFINES=$COMPDEFINES'; - -{% if solver_options.qp_solver is containing("QPOASES") %} -CFLAGS = [ CFLAGS, ' -DACADOS_WITH_QPOASES ' ]; -COMPDEFINES = [ COMPDEFINES, ' -DACADOS_WITH_QPOASES ' ]; -{%- elif solver_options.qp_solver is containing("OSQP") %} -CFLAGS = [ CFLAGS, ' -DACADOS_WITH_OSQP ' ]; -COMPDEFINES = [ COMPDEFINES, ' -DACADOS_WITH_OSQP ' ]; -{%- elif solver_options.qp_solver is containing("QPDUNES") %} -CFLAGS = [ CFLAGS, ' -DACADOS_WITH_QPDUNES ' ]; -COMPDEFINES = [ COMPDEFINES, ' -DACADOS_WITH_QPDUNES ' ]; -{%- elif solver_options.qp_solver is containing("DAQP") %} -CFLAGS = [ CFLAGS, ' -DACADOS_WITH_DAQP' ]; -COMPDEFINES = [ COMPDEFINES, ' -DACADOS_WITH_DAQP' ]; -{%- elif solver_options.qp_solver is containing("HPMPC") %} -CFLAGS = [ CFLAGS, ' -DACADOS_WITH_HPMPC ' ]; -COMPDEFINES = [ COMPDEFINES, ' -DACADOS_WITH_HPMPC ' ]; -{% endif %} - -LIB_PATH = ['-L', fullfile('{{ acados_lib_path }}')]; - -LIBS = {'-lacados', '-lhpipm', '-lblasfeo'}; - -% acados linking libraries and flags -{%- if acados_link_libs and os and os == "pc" %} -LDFLAGS = [LDFLAGS ' {{ acados_link_libs.openmp }}']; -COMPFLAGS = [COMPFLAGS ' {{ acados_link_libs.openmp }}']; -LIBS{end+1} = '{{ acados_link_libs.qpoases }}'; -LIBS{end+1} = '{{ acados_link_libs.hpmpc }}'; -LIBS{end+1} = '{{ acados_link_libs.osqp }}'; -{%- else %} - {% if solver_options.qp_solver is containing("QPOASES") %} -LIBS{end+1} = '-lqpOASES_e'; - {% endif %} - {% if solver_options.qp_solver is containing("DAQP") %} -LIBS{end+1} = '-ldaqp'; - {% endif %} -{%- endif %} - - -try - % mex('-v', '-O', CFLAGS, LDFLAGS, COMPFLAGS, COMPDEFINES, INCS{:}, ... - mex('-O', CFLAGS, LDFLAGS, COMPFLAGS, COMPDEFINES, INCS{:}, ... - LIB_PATH, LIBS{:}, SOURCES{:}, ... - '-output', 'acados_solver_sfunction_{{ model.name }}' ); -catch exception - disp('make_sfun failed with the following exception:') - disp(exception); - disp('Try adding -v to the mex command above to get more information.') - keyboard -end - -fprintf( [ '\n\nSuccessfully created sfunction:\nacados_solver_sfunction_{{ model.name }}', '.', ... - eval('mexext')] ); - - -%% print note on usage of s-function, and create I/O port names vectors -fprintf('\n\nNote: Usage of Sfunction is as follows:\n') -input_note = 'Inputs are:\n'; -i_in = 1; - -global sfun_input_names -sfun_input_names = {}; - -{%- if dims.nbx_0 > 0 and simulink_opts.inputs.lbx_0 -%} {#- lbx_0 #} -input_note = strcat(input_note, num2str(i_in), ') lbx_0 - lower bound on x for stage 0,',... - ' size [{{ dims.nbx_0 }}]\n '); -sfun_input_names = [sfun_input_names; 'lbx_0 [{{ dims.nbx_0 }}]']; -i_in = i_in + 1; -{%- endif %} - -{%- if dims.nbx_0 > 0 and simulink_opts.inputs.ubx_0 -%} {#- ubx_0 #} -input_note = strcat(input_note, num2str(i_in), ') ubx_0 - upper bound on x for stage 0,',... - ' size [{{ dims.nbx_0 }}]\n '); -sfun_input_names = [sfun_input_names; 'ubx_0 [{{ dims.nbx_0 }}]']; -i_in = i_in + 1; -{%- endif %} - -{%- if dims.np > 0 and simulink_opts.inputs.parameter_traj -%} {#- parameter_traj #} -input_note = strcat(input_note, num2str(i_in), ') parameters - concatenated for all shooting nodes 0 to N,',... - ' size [{{ (dims.N+1)*dims.np }}]\n '); -sfun_input_names = [sfun_input_names; 'parameter_traj [{{ (dims.N+1)*dims.np }}]']; -i_in = i_in + 1; -{%- endif %} - -{%- if dims.ny_0 > 0 and simulink_opts.inputs.y_ref_0 %} -input_note = strcat(input_note, num2str(i_in), ') y_ref_0, size [{{ dims.ny_0 }}]\n '); -sfun_input_names = [sfun_input_names; 'y_ref_0 [{{ dims.ny_0 }}]']; -i_in = i_in + 1; -{%- endif %} - -{%- if dims.ny > 0 and dims.N > 1 and simulink_opts.inputs.y_ref %} -input_note = strcat(input_note, num2str(i_in), ') y_ref - concatenated for shooting nodes 1 to N-1,',... - ' size [{{ (dims.N-1) * dims.ny }}]\n '); -sfun_input_names = [sfun_input_names; 'y_ref [{{ (dims.N-1) * dims.ny }}]']; -i_in = i_in + 1; -{%- endif %} - -{%- if dims.ny_e > 0 and dims.N > 0 and simulink_opts.inputs.y_ref_e %} -input_note = strcat(input_note, num2str(i_in), ') y_ref_e, size [{{ dims.ny_e }}]\n '); -sfun_input_names = [sfun_input_names; 'y_ref_e [{{ dims.ny_e }}]']; -i_in = i_in + 1; -{%- endif %} - -{%- if dims.nbx > 0 and dims.N > 1 and simulink_opts.inputs.lbx -%} {#- lbx #} -input_note = strcat(input_note, num2str(i_in), ') lbx for shooting nodes 1 to N-1, size [{{ (dims.N-1) * dims.nbx }}]\n '); -sfun_input_names = [sfun_input_names; 'lbx [{{ (dims.N-1) * dims.nbx }}]']; -i_in = i_in + 1; -{%- endif %} -{%- if dims.nbx > 0 and dims.N > 1 and simulink_opts.inputs.ubx -%} {#- ubx #} -input_note = strcat(input_note, num2str(i_in), ') ubx for shooting nodes 1 to N-1, size [{{ (dims.N-1) * dims.nbx }}]\n '); -sfun_input_names = [sfun_input_names; 'ubx [{{ (dims.N-1) * dims.nbx }}]']; -i_in = i_in + 1; -{%- endif %} - - -{%- if dims.nbx_e > 0 and dims.N > 0 and simulink_opts.inputs.lbx_e -%} {#- lbx_e #} -input_note = strcat(input_note, num2str(i_in), ') lbx_e (lbx at shooting node N), size [{{ dims.nbx_e }}]\n '); -sfun_input_names = [sfun_input_names; 'lbx_e [{{ dims.nbx_e }}]']; -i_in = i_in + 1; -{%- endif %} -{%- if dims.nbx_e > 0 and dims.N > 0 and simulink_opts.inputs.ubx_e -%} {#- ubx_e #} -input_note = strcat(input_note, num2str(i_in), ') ubx_e (ubx at shooting node N), size [{{ dims.nbx_e }}]\n '); -sfun_input_names = [sfun_input_names; 'ubx_e [{{ dims.nbx_e }}]']; -i_in = i_in + 1; -{%- endif %} - -{%- if dims.nbu > 0 and dims.N > 0 and simulink_opts.inputs.lbu -%} {#- lbu #} -input_note = strcat(input_note, num2str(i_in), ') lbu for shooting nodes 0 to N-1, size [{{ dims.N*dims.nbu }}]\n '); -sfun_input_names = [sfun_input_names; 'lbu [{{ dims.N*dims.nbu }}]']; -i_in = i_in + 1; -{%- endif -%} -{%- if dims.nbu > 0 and dims.N > 0 and simulink_opts.inputs.ubu -%} {#- ubu #} -input_note = strcat(input_note, num2str(i_in), ') ubu for shooting nodes 0 to N-1, size [{{ dims.N*dims.nbu }}]\n '); -sfun_input_names = [sfun_input_names; 'ubu [{{ dims.N*dims.nbu }}]']; -i_in = i_in + 1; -{%- endif -%} - -{%- if dims.ng > 0 and simulink_opts.inputs.lg -%} {#- lg #} -input_note = strcat(input_note, num2str(i_in), ') lg for shooting nodes 0 to N-1, size [{{ dims.N*dims.ng }}]\n '); -sfun_input_names = [sfun_input_names; 'lg [{{ dims.N*dims.ng }}]']; -i_in = i_in + 1; -{%- endif %} -{%- if dims.ng > 0 and simulink_opts.inputs.ug -%} {#- ug #} -input_note = strcat(input_note, num2str(i_in), ') ug for shooting nodes 0 to N-1, size [{{ dims.N*dims.ng }}]\n '); -sfun_input_names = [sfun_input_names; 'ug [{{ dims.N*dims.ng }}]']; -i_in = i_in + 1; -{%- endif %} - -{%- if dims.nh > 0 and simulink_opts.inputs.lh -%} {#- lh #} -input_note = strcat(input_note, num2str(i_in), ') lh for shooting nodes 0 to N-1, size [{{ dims.N*dims.nh }}]\n '); -sfun_input_names = [sfun_input_names; 'lh [{{ dims.N*dims.nh }}]']; -i_in = i_in + 1; -{%- endif %} -{%- if dims.nh > 0 and simulink_opts.inputs.uh -%} {#- uh #} -input_note = strcat(input_note, num2str(i_in), ') uh for shooting nodes 0 to N-1, size [{{ dims.N*dims.nh }}]\n '); -sfun_input_names = [sfun_input_names; 'uh [{{ dims.N*dims.nh }}]']; -i_in = i_in + 1; -{%- endif %} - -{%- if dims.nh_e > 0 and simulink_opts.inputs.lh_e -%} {#- lh_e #} -input_note = strcat(input_note, num2str(i_in), ') lh_e, size [{{ dims.nh_e }}]\n '); -sfun_input_names = [sfun_input_names; 'lh_e [{{ dims.nh_e }}]']; -i_in = i_in + 1; -{%- endif %} -{%- if dims.nh_e > 0 and simulink_opts.inputs.uh_e -%} {#- uh_e #} -input_note = strcat(input_note, num2str(i_in), ') uh_e, size [{{ dims.nh_e }}]\n '); -sfun_input_names = [sfun_input_names; 'uh_e [{{ dims.nh_e }}]']; -i_in = i_in + 1; -{%- endif %} - -{%- if dims.ny_0 > 0 and simulink_opts.inputs.cost_W_0 %} {#- cost_W_0 #} -input_note = strcat(input_note, num2str(i_in), ') cost_W_0 in column-major format, size [{{ dims.ny_0 * dims.ny_0 }}]\n '); -sfun_input_names = [sfun_input_names; 'cost_W_0 [{{ dims.ny_0 * dims.ny_0 }}]']; -i_in = i_in + 1; -{%- endif %} - -{%- if dims.ny > 0 and simulink_opts.inputs.cost_W %} {#- cost_W #} -input_note = strcat(input_note, num2str(i_in), ') cost_W in column-major format, that is set for all intermediate shooting nodes: 1 to N-1, size [{{ dims.ny * dims.ny }}]\n '); -sfun_input_names = [sfun_input_names; 'cost_W [{{ dims.ny * dims.ny }}]']; -i_in = i_in + 1; -{%- endif %} - -{%- if dims.ny_e > 0 and simulink_opts.inputs.cost_W_e %} {#- cost_W_e #} -input_note = strcat(input_note, num2str(i_in), ') cost_W_e in column-major format, size [{{ dims.ny_e * dims.ny_e }}]\n '); -sfun_input_names = [sfun_input_names; 'cost_W_e [{{ dims.ny_e * dims.ny_e }}]']; -i_in = i_in + 1; -{%- endif %} - -{%- if simulink_opts.inputs.reset_solver %} {#- reset_solver #} -input_note = strcat(input_note, num2str(i_in), ') reset_solver determines if iterate is set to all zeros before other initializations (x_init, u_init) are set and before solver is called, size [1]\n '); -sfun_input_names = [sfun_input_names; 'reset_solver [1]']; -i_in = i_in + 1; -{%- endif %} - -{%- if simulink_opts.inputs.x_init %} {#- x_init #} -input_note = strcat(input_note, num2str(i_in), ') initialization of x for all shooting nodes, size [{{ dims.nx * (dims.N+1) }}]\n '); -sfun_input_names = [sfun_input_names; 'x_init [{{ dims.nx * (dims.N+1) }}]']; -i_in = i_in + 1; -{%- endif %} - -{%- if simulink_opts.inputs.u_init %} {#- u_init #} -input_note = strcat(input_note, num2str(i_in), ') initialization of u for shooting nodes 0 to N-1, size [{{ dims.nu * (dims.N) }}]\n '); -sfun_input_names = [sfun_input_names; 'u_init [{{ dims.nu * (dims.N) }}]']; -i_in = i_in + 1; -{%- endif %} - -fprintf(input_note) - -disp(' ') - -output_note = 'Outputs are:\n'; -i_out = 0; - -global sfun_output_names -sfun_output_names = {}; - -{%- if dims.nu > 0 and simulink_opts.outputs.u0 == 1 %} -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') u0, control input at node 0, size [{{ dims.nu }}]\n '); -sfun_output_names = [sfun_output_names; 'u0 [{{ dims.nu }}]']; -{%- endif %} - -{%- if simulink_opts.outputs.utraj == 1 %} -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') utraj, control input concatenated for nodes 0 to N-1, size [{{ dims.nu * dims.N }}]\n '); -sfun_output_names = [sfun_output_names; 'utraj [{{ dims.nu * dims.N }}]']; -{%- endif %} - -{%- if simulink_opts.outputs.xtraj == 1 %} -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') xtraj, state concatenated for nodes 0 to N, size [{{ dims.nx * (dims.N + 1) }}]\n '); -sfun_output_names = [sfun_output_names; 'xtraj [{{ dims.nx * (dims.N + 1) }}]']; -{%- endif %} - -{%- if simulink_opts.outputs.solver_status == 1 %} -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') acados solver status (0 = SUCCESS)\n '); -sfun_output_names = [sfun_output_names; 'solver_status']; -{%- endif %} - -{%- if simulink_opts.outputs.cost_value == 1 %} -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') cost function value\n '); -sfun_output_names = [sfun_output_names; 'cost_value']; -{%- endif %} - - -{%- if simulink_opts.outputs.KKT_residual == 1 %} -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') KKT residual\n '); -sfun_output_names = [sfun_output_names; 'KKT_residual']; -{%- endif %} - -{%- if simulink_opts.outputs.KKT_residuals == 1 %} -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') KKT residuals, size [4] (stat, eq, ineq, comp)\n '); -sfun_output_names = [sfun_output_names; 'KKT_residuals [4]']; -{%- endif %} - -{%- if dims.N > 0 and simulink_opts.outputs.x1 == 1 %} -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') x1, state at node 1\n '); -sfun_output_names = [sfun_output_names; 'x1']; -{%- endif %} - -{%- if simulink_opts.outputs.CPU_time == 1 %} -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') CPU time\n '); -sfun_output_names = [sfun_output_names; 'CPU_time']; -{%- endif %} - -{%- if simulink_opts.outputs.CPU_time_sim == 1 %} -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') CPU time integrator\n '); -sfun_output_names = [sfun_output_names; 'CPU_time_sim']; -{%- endif %} - -{%- if simulink_opts.outputs.CPU_time_qp == 1 %} -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') CPU time QP solution\n '); -sfun_output_names = [sfun_output_names; 'CPU_time_qp']; -{%- endif %} - -{%- if simulink_opts.outputs.CPU_time_lin == 1 %} -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') CPU time linearization (including integrator)\n '); -sfun_output_names = [sfun_output_names; 'CPU_time_lin']; -{%- endif %} - -{%- if simulink_opts.outputs.sqp_iter == 1 %} -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') SQP iterations\n '); -sfun_output_names = [sfun_output_names; 'sqp_iter']; -{%- endif %} - -fprintf(output_note) - -% The mask drawing command is: -% --- -% global sfun_input_names sfun_output_names -% for i = 1:length(sfun_input_names) -% port_label('input', i, sfun_input_names{i}) -% end -% for i = 1:length(sfun_output_names) -% port_label('output', i, sfun_output_names{i}) -% end -% --- -% It can be used by copying it in sfunction/Mask/Edit mask/Icon drawing commands -% (you can access it wirth ctrl+M on the s-function) \ No newline at end of file diff --git a/third_party/acados/acados_template/c_templates_tera/matlab_templates/make_sfun_sim.in.m b/third_party/acados/acados_template/c_templates_tera/matlab_templates/make_sfun_sim.in.m deleted file mode 100644 index e4c32a8c19..0000000000 --- a/third_party/acados/acados_template/c_templates_tera/matlab_templates/make_sfun_sim.in.m +++ /dev/null @@ -1,137 +0,0 @@ -% -% Copyright (c) The acados authors. -% -% This file is part of acados. -% -% The 2-Clause BSD License -% -% Redistribution and use in source and binary forms, with or without -% modification, are permitted provided that the following conditions are met: -% -% 1. Redistributions of source code must retain the above copyright notice, -% this list of conditions and the following disclaimer. -% -% 2. Redistributions in binary form must reproduce the above copyright notice, -% this list of conditions and the following disclaimer in the documentation -% and/or other materials provided with the distribution. -% -% THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -% AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -% IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -% ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -% LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -% CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -% SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -% INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -% CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -% ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -% POSSIBILITY OF SUCH DAMAGE.; - -% - -SOURCES = [ 'acados_sim_solver_sfunction_{{ model.name }}.c ', ... - 'acados_sim_solver_{{ model.name }}.c ', ... - {%- if solver_options.integrator_type == 'ERK' %} - '{{ model.name }}_model/{{ model.name }}_expl_ode_fun.c ',... - '{{ model.name }}_model/{{ model.name }}_expl_vde_forw.c ',... - '{{ model.name }}_model/{{ model.name }}_expl_vde_adj.c ',... - {%- if solver_options.hessian_approx == 'EXACT' %} - '{{ model.name }}_model/{{ model.name }}_expl_ode_hess.c ',... - {%- endif %} - {%- elif solver_options.integrator_type == "IRK" %} - '{{ model.name }}_model/{{ model.name }}_impl_dae_fun.c ', ... - '{{ model.name }}_model/{{ model.name }}_impl_dae_fun_jac_x_xdot_z.c ', ... - '{{ model.name }}_model/{{ model.name }}_impl_dae_jac_x_xdot_u_z.c ', ... - {%- if solver_options.hessian_approx == 'EXACT' %} - '{{ model.name }}_model/{{ model.name }}_impl_dae_hess.c ',... - {%- endif %} - {%- elif solver_options.integrator_type == "GNSF" %} - {%- if model.gnsf.purely_linear != 1 %} - '{{ model.name }}_model/{{ model.name }}_gnsf_phi_fun.c ',... - '{{ model.name }}_model/{{ model.name }}_gnsf_phi_fun_jac_y.c ',... - '{{ model.name }}_model/{{ model.name }}_gnsf_phi_jac_y_uhat.c ',... - {%- if model.gnsf.nontrivial_f_LO == 1 %} - '{{ model.name }}_model/{{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz.c ',... - {%- endif %} - {%- endif %} - '{{ model.name }}_model/{{ model.name }}_gnsf_get_matrices_fun.c ',... - {%- endif %} - ]; - -INC_PATH = '{{ acados_include_path }}'; - -INCS = [ ' -I', fullfile(INC_PATH, 'blasfeo', 'include'), ... - ' -I', fullfile(INC_PATH, 'hpipm', 'include'), ... - ' -I', INC_PATH, ' -I', fullfile(INC_PATH, 'acados'), ' ']; - -CFLAGS = ' -O'; - -LIB_PATH = '{{ acados_lib_path }}'; - -LIBS = '-lacados -lblasfeo -lhpipm'; - -try - % eval( [ 'mex -v -output acados_sim_solver_sfunction_{{ model.name }} ', ... - eval( [ 'mex -output acados_sim_solver_sfunction_{{ model.name }} ', ... - CFLAGS, INCS, ' ', SOURCES, ' -L', LIB_PATH, ' ', LIBS ]); - -catch exception - disp('make_sfun failed with the following exception:') - disp(exception); - disp('Try adding -v to the mex command above to get more information.') - keyboard -end - - -fprintf( [ '\n\nSuccessfully created sfunction:\nacados_sim_solver_sfunction_{{ model.name }}', '.', ... - eval('mexext')] ); - - -global sfun_sim_input_names -sfun_sim_input_names = {}; - -%% print note on usage of s-function -fprintf('\n\nNote: Usage of Sfunction is as follows:\n') -input_note = 'Inputs are:\n1) x0, initial state, size [{{ dims.nx }}]\n '; -i_in = 2; -sfun_sim_input_names = [sfun_sim_input_names; 'x0 [{{ dims.nx }}]']; - -{%- if dims.nu > 0 %} -input_note = strcat(input_note, num2str(i_in), ') u, size [{{ dims.nu }}]\n '); -i_in = i_in + 1; -sfun_sim_input_names = [sfun_sim_input_names; 'u [{{ dims.nu }}]']; -{%- endif %} - -{%- if dims.np > 0 %} -input_note = strcat(input_note, num2str(i_in), ') parameters, size [{{ dims.np }}]\n '); -i_in = i_in + 1; -sfun_sim_input_names = [sfun_sim_input_names; 'p [{{ dims.np }}]']; -{%- endif %} - - -fprintf(input_note) - -disp(' ') - -global sfun_sim_output_names -sfun_sim_output_names = {}; - -output_note = strcat('Outputs are:\n', ... - '1) x1 - simulated state, size [{{ dims.nx }}]\n'); -sfun_sim_output_names = [sfun_sim_output_names; 'x1 [{{ dims.nx }}]']; - -fprintf(output_note) - - -% The mask drawing command is: -% --- -% global sfun_sim_input_names sfun_sim_output_names -% for i = 1:length(sfun_sim_input_names) -% port_label('input', i, sfun_sim_input_names{i}) -% end -% for i = 1:length(sfun_sim_output_names) -% port_label('output', i, sfun_sim_output_names{i}) -% end -% --- -% It can be used by copying it in sfunction/Mask/Edit mask/Icon drawing commands -% (you can access it wirth ctrl+M on the s-function) \ No newline at end of file diff --git a/third_party/acados/acados_template/c_templates_tera/matlab_templates/mex_solver.in.m b/third_party/acados/acados_template/c_templates_tera/matlab_templates/mex_solver.in.m deleted file mode 100644 index 3743212830..0000000000 --- a/third_party/acados/acados_template/c_templates_tera/matlab_templates/mex_solver.in.m +++ /dev/null @@ -1,270 +0,0 @@ -% -% Copyright (c) The acados authors. -% -% This file is part of acados. -% -% The 2-Clause BSD License -% -% Redistribution and use in source and binary forms, with or without -% modification, are permitted provided that the following conditions are met: -% -% 1. Redistributions of source code must retain the above copyright notice, -% this list of conditions and the following disclaimer. -% -% 2. Redistributions in binary form must reproduce the above copyright notice, -% this list of conditions and the following disclaimer in the documentation -% and/or other materials provided with the distribution. -% -% THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -% AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -% IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -% ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -% LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -% CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -% SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -% INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -% CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -% ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -% POSSIBILITY OF SUCH DAMAGE.; - -% - -classdef {{ model.name }}_mex_solver < handle - - properties - C_ocp - C_ocp_ext_fun - cost_ext_fun_type - cost_ext_fun_type_e - N - name - code_gen_dir - end % properties - - - - methods - - % constructor - function obj = {{ model.name }}_mex_solver() - make_mex_{{ model.name }}(); - [obj.C_ocp, obj.C_ocp_ext_fun] = acados_mex_create_{{ model.name }}(); - % to have path to destructor when changing directory - addpath('.') - obj.cost_ext_fun_type = '{{ cost.cost_ext_fun_type }}'; - obj.cost_ext_fun_type_e = '{{ cost.cost_ext_fun_type_e }}'; - obj.N = {{ dims.N }}; - obj.name = '{{ model.name }}'; - obj.code_gen_dir = pwd(); - end - - % destructor - function delete(obj) - disp("delete template..."); - return_dir = pwd(); - cd(obj.code_gen_dir); - if ~isempty(obj.C_ocp) - acados_mex_free_{{ model.name }}(obj.C_ocp); - end - cd(return_dir); - disp("done."); - end - - % solve - function solve(obj) - acados_mex_solve_{{ model.name }}(obj.C_ocp); - end - - % set -- borrowed from MEX interface - function set(varargin) - obj = varargin{1}; - field = varargin{2}; - value = varargin{3}; - if ~isa(field, 'char') - error('field must be a char vector, use '' '''); - end - if nargin==3 - acados_mex_set_{{ model.name }}(obj.cost_ext_fun_type, obj.cost_ext_fun_type_e, obj.C_ocp, obj.C_ocp_ext_fun, field, value); - elseif nargin==4 - stage = varargin{4}; - acados_mex_set_{{ model.name }}(obj.cost_ext_fun_type, obj.cost_ext_fun_type_e, obj.C_ocp, obj.C_ocp_ext_fun, field, value, stage); - else - disp('acados_ocp.set: wrong number of input arguments (2 or 3 allowed)'); - end - end - - function value = get_cost(obj) - value = ocp_get_cost(obj.C_ocp); - end - - % get -- borrowed from MEX interface - function value = get(varargin) - % usage: - % obj.get(field, value, [stage]) - obj = varargin{1}; - field = varargin{2}; - if any(strfind('sens', field)) - error('field sens* (sensitivities of optimal solution) not yet supported for templated MEX.') - end - if ~isa(field, 'char') - error('field must be a char vector, use '' '''); - end - - if nargin==2 - value = ocp_get(obj.C_ocp, field); - elseif nargin==3 - stage = varargin{3}; - value = ocp_get(obj.C_ocp, field, stage); - else - disp('acados_ocp.get: wrong number of input arguments (1 or 2 allowed)'); - end - end - - - function [] = store_iterate(varargin) - %%% Stores the current iterate of the ocp solver in a json file. - %%% param1: filename: if not set, use model_name + timestamp + '.json' - %%% param2: overwrite: if false and filename exists add timestamp to filename - - obj = varargin{1}; - filename = ''; - overwrite = false; - - if nargin>=2 - filename = varargin{2}; - if ~isa(filename, 'char') - error('filename must be a char vector, use '' '''); - end - end - - if nargin==3 - overwrite = varargin{3}; - end - - if nargin > 3 - disp('acados_ocp.get: wrong number of input arguments (1 or 2 allowed)'); - end - - if strcmp(filename,'') - filename = [obj.name '_iterate.json']; - end - if ~overwrite - % append timestamp - if exist(filename, 'file') - filename = filename(1:end-5); - filename = [filename '_' datestr(now,'yyyy-mm-dd-HH:MM:SS') '.json']; - end - end - filename = fullfile(pwd, filename); - - % get iterate: - solution = struct(); - for i=0:obj.N - solution.(['x_' num2str(i)]) = obj.get('x', i); - solution.(['lam_' num2str(i)]) = obj.get('lam', i); - solution.(['t_' num2str(i)]) = obj.get('t', i); - solution.(['sl_' num2str(i)]) = obj.get('sl', i); - solution.(['su_' num2str(i)]) = obj.get('su', i); - end - for i=0:obj.N-1 - solution.(['z_' num2str(i)]) = obj.get('z', i); - solution.(['u_' num2str(i)]) = obj.get('u', i); - solution.(['pi_' num2str(i)]) = obj.get('pi', i); - end - - acados_folder = getenv('ACADOS_INSTALL_DIR'); - addpath(fullfile(acados_folder, 'external', 'jsonlab')); - savejson('', solution, filename); - - json_string = savejson('', solution, 'ForceRootName', 0); - - fid = fopen(filename, 'w'); - if fid == -1, error('store_iterate: Cannot create JSON file'); end - fwrite(fid, json_string, 'char'); - fclose(fid); - - disp(['stored current iterate in ' filename]); - end - - - function [] = load_iterate(obj, filename) - %%% Loads the iterate stored in json file with filename into the ocp solver. - acados_folder = getenv('ACADOS_INSTALL_DIR'); - addpath(fullfile(acados_folder, 'external', 'jsonlab')); - filename = fullfile(pwd, filename); - - if ~exist(filename, 'file') - error(['load_iterate: failed, file does not exist: ' filename]) - end - - solution = loadjson(filename); - keys = fieldnames(solution); - - for k = 1:numel(keys) - key = keys{k}; - key_parts = strsplit(key, '_'); - field = key_parts{1}; - stage = key_parts{2}; - - val = solution.(key); - - % check if array is empty (can happen for z) - if numel(val) > 0 - obj.set(field, val, str2num(stage)) - end - end - end - - - % print - function print(varargin) - if nargin < 2 - field = 'stat'; - else - field = varargin{2}; - end - - obj = varargin{1}; - - if strcmp(field, 'stat') - stat = obj.get('stat'); - {%- if solver_options.nlp_solver_type == "SQP" %} - fprintf('\niter\tres_stat\tres_eq\t\tres_ineq\tres_comp\tqp_stat\tqp_iter\talpha'); - if size(stat,2)>8 - fprintf('\tqp_res_stat\tqp_res_eq\tqp_res_ineq\tqp_res_comp'); - end - fprintf('\n'); - for jj=1:size(stat,1) - fprintf('%d\t%e\t%e\t%e\t%e\t%d\t%d\t%e', stat(jj,1), stat(jj,2), stat(jj,3), stat(jj,4), stat(jj,5), stat(jj,6), stat(jj,7), stat(jj, 8)); - if size(stat,2)>8 - fprintf('\t%e\t%e\t%e\t%e', stat(jj,9), stat(jj,10), stat(jj,11), stat(jj,12)); - end - fprintf('\n'); - end - fprintf('\n'); - {%- else %} - fprintf('\niter\tqp_status\tqp_iter'); - if size(stat,2)>3 - fprintf('\tqp_res_stat\tqp_res_eq\tqp_res_ineq\tqp_res_comp'); - end - fprintf('\n'); - for jj=1:size(stat,1) - fprintf('%d\t%d\t\t%d', stat(jj,1), stat(jj,2), stat(jj,3)); - if size(stat,2)>3 - fprintf('\t%e\t%e\t%e\t%e', stat(jj,4), stat(jj,5), stat(jj,6), stat(jj,7)); - end - fprintf('\n'); - end - {% endif %} - - else - fprintf('unsupported field in function print of acados_ocp.print, got %s', field); - keyboard - end - - end - - end % methods - -end % class - diff --git a/third_party/acados/acados_template/c_templates_tera/model.in.h b/third_party/acados/acados_template/c_templates_tera/model.in.h deleted file mode 100644 index e5059df9ff..0000000000 --- a/third_party/acados/acados_template/c_templates_tera/model.in.h +++ /dev/null @@ -1,218 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - -#ifndef {{ model.name }}_MODEL -#define {{ model.name }}_MODEL - -#ifdef __cplusplus -extern "C" { -#endif - -{%- if solver_options.hessian_approx %} - {%- set hessian_approx = solver_options.hessian_approx %} -{%- elif solver_options.sens_hess %} - {%- set hessian_approx = "EXACT" %} -{%- else %} - {%- set hessian_approx = "GAUSS_NEWTON" %} -{%- endif %} - -{% if solver_options.integrator_type == "IRK" or solver_options.integrator_type == "LIFTED_IRK" %} - {% if model.dyn_ext_fun_type == "casadi" %} -// implicit ODE: function -int {{ model.name }}_impl_dae_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_impl_dae_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_impl_dae_fun_sparsity_in(int); -const int *{{ model.name }}_impl_dae_fun_sparsity_out(int); -int {{ model.name }}_impl_dae_fun_n_in(void); -int {{ model.name }}_impl_dae_fun_n_out(void); - -// implicit ODE: function + jacobians -int {{ model.name }}_impl_dae_fun_jac_x_xdot_z(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_impl_dae_fun_jac_x_xdot_z_work(int *, int *, int *, int *); -const int *{{ model.name }}_impl_dae_fun_jac_x_xdot_z_sparsity_in(int); -const int *{{ model.name }}_impl_dae_fun_jac_x_xdot_z_sparsity_out(int); -int {{ model.name }}_impl_dae_fun_jac_x_xdot_z_n_in(void); -int {{ model.name }}_impl_dae_fun_jac_x_xdot_z_n_out(void); - -// implicit ODE: jacobians only -int {{ model.name }}_impl_dae_jac_x_xdot_u_z(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_impl_dae_jac_x_xdot_u_z_work(int *, int *, int *, int *); -const int *{{ model.name }}_impl_dae_jac_x_xdot_u_z_sparsity_in(int); -const int *{{ model.name }}_impl_dae_jac_x_xdot_u_z_sparsity_out(int); -int {{ model.name }}_impl_dae_jac_x_xdot_u_z_n_in(void); -int {{ model.name }}_impl_dae_jac_x_xdot_u_z_n_out(void); - -// implicit ODE - for lifted_irk -int {{ model.name }}_impl_dae_fun_jac_x_xdot_u(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_impl_dae_fun_jac_x_xdot_u_work(int *, int *, int *, int *); -const int *{{ model.name }}_impl_dae_fun_jac_x_xdot_u_sparsity_in(int); -const int *{{ model.name }}_impl_dae_fun_jac_x_xdot_u_sparsity_out(int); -int {{ model.name }}_impl_dae_fun_jac_x_xdot_u_n_in(void); -int {{ model.name }}_impl_dae_fun_jac_x_xdot_u_n_out(void); - - {%- if hessian_approx == "EXACT" %} -// implicit ODE - hessian -int {{ model.name }}_impl_dae_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_impl_dae_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_impl_dae_hess_sparsity_in(int); -const int *{{ model.name }}_impl_dae_hess_sparsity_out(int); -int {{ model.name }}_impl_dae_hess_n_in(void); -int {{ model.name }}_impl_dae_hess_n_out(void); - {% endif %} - {% else %}{# ext_fun_type #} - {%- if hessian_approx == "EXACT" %} -int {{ model.dyn_impl_dae_hess }}(void **, void **, void *); - {% endif %} -int {{ model.dyn_impl_dae_fun_jac }}(void **, void **, void *); -int {{ model.dyn_impl_dae_jac }}(void **, void **, void *); -int {{ model.dyn_impl_dae_fun }}(void **, void **, void *); - {% endif %}{# ext_fun_type #} - -{% elif solver_options.integrator_type == "GNSF" %} -/* GNSF Functions */ - {% if model.gnsf.purely_linear != 1 %} -// phi_fun -int {{ model.name }}_gnsf_phi_fun(const double** arg, double** res, int* iw, double* w, void *mem); -int {{ model.name }}_gnsf_phi_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_gnsf_phi_fun_sparsity_in(int); -const int *{{ model.name }}_gnsf_phi_fun_sparsity_out(int); -int {{ model.name }}_gnsf_phi_fun_n_in(void); -int {{ model.name }}_gnsf_phi_fun_n_out(void); - -// phi_fun_jac_y -int {{ model.name }}_gnsf_phi_fun_jac_y(const double** arg, double** res, int* iw, double* w, void *mem); -int {{ model.name }}_gnsf_phi_fun_jac_y_work(int *, int *, int *, int *); -const int *{{ model.name }}_gnsf_phi_fun_jac_y_sparsity_in(int); -const int *{{ model.name }}_gnsf_phi_fun_jac_y_sparsity_out(int); -int {{ model.name }}_gnsf_phi_fun_jac_y_n_in(void); -int {{ model.name }}_gnsf_phi_fun_jac_y_n_out(void); - -// phi_jac_y_uhat -int {{ model.name }}_gnsf_phi_jac_y_uhat(const double** arg, double** res, int* iw, double* w, void *mem); -int {{ model.name }}_gnsf_phi_jac_y_uhat_work(int *, int *, int *, int *); -const int *{{ model.name }}_gnsf_phi_jac_y_uhat_sparsity_in(int); -const int *{{ model.name }}_gnsf_phi_jac_y_uhat_sparsity_out(int); -int {{ model.name }}_gnsf_phi_jac_y_uhat_n_in(void); -int {{ model.name }}_gnsf_phi_jac_y_uhat_n_out(void); - {% if model.gnsf.nontrivial_f_LO == 1 %} -// f_lo_fun_jac_x1k1uz -int {{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz(const double** arg, double** res, int* iw, double* w, void *mem); -int {{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz_work(int *, int *, int *, int *); -const int *{{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz_sparsity_in(int); -const int *{{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz_sparsity_out(int); -int {{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz_n_in(void); -int {{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz_n_out(void); - {%- endif %} - {%- endif %} -// used to import model matrices -int {{ model.name }}_gnsf_get_matrices_fun(const double** arg, double** res, int* iw, double* w, void *mem); -int {{ model.name }}_gnsf_get_matrices_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_gnsf_get_matrices_fun_sparsity_in(int); -const int *{{ model.name }}_gnsf_get_matrices_fun_sparsity_out(int); -int {{ model.name }}_gnsf_get_matrices_fun_n_in(void); -int {{ model.name }}_gnsf_get_matrices_fun_n_out(void); - -{% elif solver_options.integrator_type == "ERK" %} -/* explicit ODE */ - -// explicit ODE -int {{ model.name }}_expl_ode_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_expl_ode_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_expl_ode_fun_sparsity_in(int); -const int *{{ model.name }}_expl_ode_fun_sparsity_out(int); -int {{ model.name }}_expl_ode_fun_n_in(void); -int {{ model.name }}_expl_ode_fun_n_out(void); - -// explicit forward VDE -int {{ model.name }}_expl_vde_forw(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_expl_vde_forw_work(int *, int *, int *, int *); -const int *{{ model.name }}_expl_vde_forw_sparsity_in(int); -const int *{{ model.name }}_expl_vde_forw_sparsity_out(int); -int {{ model.name }}_expl_vde_forw_n_in(void); -int {{ model.name }}_expl_vde_forw_n_out(void); - -// explicit adjoint VDE -int {{ model.name }}_expl_vde_adj(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_expl_vde_adj_work(int *, int *, int *, int *); -const int *{{ model.name }}_expl_vde_adj_sparsity_in(int); -const int *{{ model.name }}_expl_vde_adj_sparsity_out(int); -int {{ model.name }}_expl_vde_adj_n_in(void); -int {{ model.name }}_expl_vde_adj_n_out(void); - -{%- if hessian_approx == "EXACT" %} -int {{ model.name }}_expl_ode_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_expl_ode_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_expl_ode_hess_sparsity_in(int); -const int *{{ model.name }}_expl_ode_hess_sparsity_out(int); -int {{ model.name }}_expl_ode_hess_n_in(void); -int {{ model.name }}_expl_ode_hess_n_out(void); -{%- endif %} - -{% elif solver_options.integrator_type == "DISCRETE" %} - -{% if model.dyn_ext_fun_type == "casadi" %} -int {{ model.name }}_dyn_disc_phi_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_dyn_disc_phi_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_dyn_disc_phi_fun_sparsity_in(int); -const int *{{ model.name }}_dyn_disc_phi_fun_sparsity_out(int); -int {{ model.name }}_dyn_disc_phi_fun_n_in(void); -int {{ model.name }}_dyn_disc_phi_fun_n_out(void); - -int {{ model.name }}_dyn_disc_phi_fun_jac(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_dyn_disc_phi_fun_jac_work(int *, int *, int *, int *); -const int *{{ model.name }}_dyn_disc_phi_fun_jac_sparsity_in(int); -const int *{{ model.name }}_dyn_disc_phi_fun_jac_sparsity_out(int); -int {{ model.name }}_dyn_disc_phi_fun_jac_n_in(void); -int {{ model.name }}_dyn_disc_phi_fun_jac_n_out(void); - -{%- if hessian_approx == "EXACT" %} -int {{ model.name }}_dyn_disc_phi_fun_jac_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_dyn_disc_phi_fun_jac_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_dyn_disc_phi_fun_jac_hess_sparsity_in(int); -const int *{{ model.name }}_dyn_disc_phi_fun_jac_hess_sparsity_out(int); -int {{ model.name }}_dyn_disc_phi_fun_jac_hess_n_in(void); -int {{ model.name }}_dyn_disc_phi_fun_jac_hess_n_out(void); -{%- endif %} -{% else %} - {%- if hessian_approx == "EXACT" %} -int {{ model.dyn_disc_fun_jac_hess }}(void **, void **, void *); - {% endif %} -int {{ model.dyn_disc_fun_jac }}(void **, void **, void *); -int {{ model.dyn_disc_fun }}(void **, void **, void *); -{% endif %} - - -{% endif %} - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // {{ model.name }}_MODEL diff --git a/third_party/acados/acados_template/casadi_function_generation.py b/third_party/acados/acados_template/casadi_function_generation.py deleted file mode 100644 index 6373a2809d..0000000000 --- a/third_party/acados/acados_template/casadi_function_generation.py +++ /dev/null @@ -1,708 +0,0 @@ -# -# Copyright (c) The acados authors. -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# - -import os -import casadi as ca -from .utils import is_empty, casadi_length - - -def get_casadi_symbol(x): - if isinstance(x, ca.MX): - return ca.MX.sym - elif isinstance(x, ca.SX): - return ca.SX.sym - else: - raise TypeError("Expected casadi SX or MX.") - -################ -# Dynamics -################ - - -def generate_c_code_discrete_dynamics( model, opts ): - - casadi_codegen_opts = dict(mex=False, casadi_int='int', casadi_real='double') - - # load model - x = model.x - u = model.u - p = model.p - phi = model.disc_dyn_expr - model_name = model.name - nx = casadi_length(x) - - symbol = get_casadi_symbol(x) - # assume nx1 = nx !!! - lam = symbol('lam', nx, 1) - - # generate jacobians - ux = ca.vertcat(u,x) - jac_ux = ca.jacobian(phi, ux) - # generate adjoint - adj_ux = ca.jtimes(phi, ux, lam, True) - # generate hessian - hess_ux = ca.jacobian(adj_ux, ux) - - # change directory - cwd = os.getcwd() - model_dir = os.path.abspath(os.path.join(opts["code_export_directory"], f'{model_name}_model')) - if not os.path.exists(model_dir): - os.makedirs(model_dir) - os.chdir(model_dir) - - # set up & generate ca.Functions - fun_name = model_name + '_dyn_disc_phi_fun' - phi_fun = ca.Function(fun_name, [x, u, p], [phi]) - phi_fun.generate(fun_name, casadi_codegen_opts) - - fun_name = model_name + '_dyn_disc_phi_fun_jac' - phi_fun_jac_ut_xt = ca.Function(fun_name, [x, u, p], [phi, jac_ux.T]) - phi_fun_jac_ut_xt.generate(fun_name, casadi_codegen_opts) - - fun_name = model_name + '_dyn_disc_phi_fun_jac_hess' - phi_fun_jac_ut_xt_hess = ca.Function(fun_name, [x, u, lam, p], [phi, jac_ux.T, hess_ux]) - phi_fun_jac_ut_xt_hess.generate(fun_name, casadi_codegen_opts) - - os.chdir(cwd) - return - - - -def generate_c_code_explicit_ode( model, opts ): - - casadi_codegen_opts = dict(mex=False, casadi_int='int', casadi_real='double') - - generate_hess = opts["generate_hess"] - - # load model - x = model.x - u = model.u - p = model.p - f_expl = model.f_expl_expr - model_name = model.name - - ## get model dimensions - nx = x.size()[0] - nu = u.size()[0] - - symbol = get_casadi_symbol(x) - - ## set up functions to be exported - Sx = symbol('Sx', nx, nx) - Sp = symbol('Sp', nx, nu) - lambdaX = symbol('lambdaX', nx, 1) - - fun_name = model_name + '_expl_ode_fun' - - ## Set up functions - expl_ode_fun = ca.Function(fun_name, [x, u, p], [f_expl]) - - vdeX = ca.jtimes(f_expl,x,Sx) - vdeP = ca.jacobian(f_expl,u) + ca.jtimes(f_expl,x,Sp) - - fun_name = model_name + '_expl_vde_forw' - - expl_vde_forw = ca.Function(fun_name, [x, Sx, Sp, u, p], [f_expl, vdeX, vdeP]) - - adj = ca.jtimes(f_expl, ca.vertcat(x, u), lambdaX, True) - - fun_name = model_name + '_expl_vde_adj' - expl_vde_adj = ca.Function(fun_name, [x, lambdaX, u, p], [adj]) - - if generate_hess: - S_forw = ca.vertcat(ca.horzcat(Sx, Sp), ca.horzcat(ca.DM.zeros(nu,nx), ca.DM.eye(nu))) - hess = ca.mtimes(ca.transpose(S_forw),ca.jtimes(adj, ca.vertcat(x,u), S_forw)) - hess2 = [] - for j in range(nx+nu): - for i in range(j,nx+nu): - hess2 = ca.vertcat(hess2, hess[i,j]) - - fun_name = model_name + '_expl_ode_hess' - expl_ode_hess = ca.Function(fun_name, [x, Sx, Sp, lambdaX, u, p], [adj, hess2]) - - # change directory - cwd = os.getcwd() - model_dir = os.path.abspath(os.path.join(opts["code_export_directory"], f'{model_name}_model')) - if not os.path.exists(model_dir): - os.makedirs(model_dir) - os.chdir(model_dir) - - # generate C code - fun_name = model_name + '_expl_ode_fun' - expl_ode_fun.generate(fun_name, casadi_codegen_opts) - - fun_name = model_name + '_expl_vde_forw' - expl_vde_forw.generate(fun_name, casadi_codegen_opts) - - fun_name = model_name + '_expl_vde_adj' - expl_vde_adj.generate(fun_name, casadi_codegen_opts) - - if generate_hess: - fun_name = model_name + '_expl_ode_hess' - expl_ode_hess.generate(fun_name, casadi_codegen_opts) - os.chdir(cwd) - - return - - -def generate_c_code_implicit_ode( model, opts ): - - casadi_codegen_opts = dict(mex=False, casadi_int='int', casadi_real='double') - - # load model - x = model.x - xdot = model.xdot - u = model.u - z = model.z - p = model.p - f_impl = model.f_impl_expr - model_name = model.name - - # get model dimensions - nx = casadi_length(x) - nz = casadi_length(z) - - # generate jacobians - jac_x = ca.jacobian(f_impl, x) - jac_xdot = ca.jacobian(f_impl, xdot) - jac_u = ca.jacobian(f_impl, u) - jac_z = ca.jacobian(f_impl, z) - - # Set up functions - p = model.p - fun_name = model_name + '_impl_dae_fun' - impl_dae_fun = ca.Function(fun_name, [x, xdot, u, z, p], [f_impl]) - - fun_name = model_name + '_impl_dae_fun_jac_x_xdot_z' - impl_dae_fun_jac_x_xdot_z = ca.Function(fun_name, [x, xdot, u, z, p], [f_impl, jac_x, jac_xdot, jac_z]) - - fun_name = model_name + '_impl_dae_fun_jac_x_xdot_u_z' - impl_dae_fun_jac_x_xdot_u_z = ca.Function(fun_name, [x, xdot, u, z, p], [f_impl, jac_x, jac_xdot, jac_u, jac_z]) - - fun_name = model_name + '_impl_dae_fun_jac_x_xdot_u' - impl_dae_fun_jac_x_xdot_u = ca.Function(fun_name, [x, xdot, u, z, p], [f_impl, jac_x, jac_xdot, jac_u]) - - fun_name = model_name + '_impl_dae_jac_x_xdot_u_z' - impl_dae_jac_x_xdot_u_z = ca.Function(fun_name, [x, xdot, u, z, p], [jac_x, jac_xdot, jac_u, jac_z]) - - if opts["generate_hess"]: - x_xdot_z_u = ca.vertcat(x, xdot, z, u) - symbol = get_casadi_symbol(x) - multiplier = symbol('multiplier', nx + nz) - ADJ = ca.jtimes(f_impl, x_xdot_z_u, multiplier, True) - HESS = ca.jacobian(ADJ, x_xdot_z_u) - fun_name = model_name + '_impl_dae_hess' - impl_dae_hess = ca.Function(fun_name, [x, xdot, u, z, multiplier, p], [HESS]) - - # change directory - cwd = os.getcwd() - model_dir = os.path.abspath(os.path.join(opts["code_export_directory"], f'{model_name}_model')) - if not os.path.exists(model_dir): - os.makedirs(model_dir) - os.chdir(model_dir) - - # generate C code - fun_name = model_name + '_impl_dae_fun' - impl_dae_fun.generate(fun_name, casadi_codegen_opts) - - fun_name = model_name + '_impl_dae_fun_jac_x_xdot_z' - impl_dae_fun_jac_x_xdot_z.generate(fun_name, casadi_codegen_opts) - - fun_name = model_name + '_impl_dae_jac_x_xdot_u_z' - impl_dae_jac_x_xdot_u_z.generate(fun_name, casadi_codegen_opts) - - fun_name = model_name + '_impl_dae_fun_jac_x_xdot_u_z' - impl_dae_fun_jac_x_xdot_u_z.generate(fun_name, casadi_codegen_opts) - - fun_name = model_name + '_impl_dae_fun_jac_x_xdot_u' - impl_dae_fun_jac_x_xdot_u.generate(fun_name, casadi_codegen_opts) - - if opts["generate_hess"]: - fun_name = model_name + '_impl_dae_hess' - impl_dae_hess.generate(fun_name, casadi_codegen_opts) - - os.chdir(cwd) - return - - -def generate_c_code_gnsf( model, opts ): - - casadi_codegen_opts = dict(mex=False, casadi_int='int', casadi_real='double') - - model_name = model.name - - # set up directory - cwd = os.getcwd() - model_dir = os.path.abspath(os.path.join(opts["code_export_directory"], f'{model_name}_model')) - if not os.path.exists(model_dir): - os.makedirs(model_dir) - os.chdir(model_dir) - - # obtain gnsf dimensions - get_matrices_fun = model.get_matrices_fun - phi_fun = model.phi_fun - - size_gnsf_A = get_matrices_fun.size_out(0) - gnsf_nx1 = size_gnsf_A[1] - gnsf_nz1 = size_gnsf_A[0] - size_gnsf_A[1] - gnsf_nuhat = max(phi_fun.size_in(1)) - gnsf_ny = max(phi_fun.size_in(0)) - gnsf_nout = max(phi_fun.size_out(0)) - - # set up expressions - # if the model uses ca.MX because of cost/constraints - # the DAE can be exported as ca.SX -> detect GNSF in Matlab - # -> evaluated ca.SX GNSF functions with ca.MX. - u = model.u - symbol = get_casadi_symbol(u) - - y = symbol("y", gnsf_ny, 1) - uhat = symbol("uhat", gnsf_nuhat, 1) - p = model.p - x1 = symbol("gnsf_x1", gnsf_nx1, 1) - x1dot = symbol("gnsf_x1dot", gnsf_nx1, 1) - z1 = symbol("gnsf_z1", gnsf_nz1, 1) - dummy = symbol("gnsf_dummy", 1, 1) - empty_var = symbol("gnsf_empty_var", 0, 0) - - ## generate C code - fun_name = model_name + '_gnsf_phi_fun' - phi_fun_ = ca.Function(fun_name, [y, uhat, p], [phi_fun(y, uhat, p)]) - phi_fun_.generate(fun_name, casadi_codegen_opts) - - fun_name = model_name + '_gnsf_phi_fun_jac_y' - phi_fun_jac_y = model.phi_fun_jac_y - phi_fun_jac_y_ = ca.Function(fun_name, [y, uhat, p], phi_fun_jac_y(y, uhat, p)) - phi_fun_jac_y_.generate(fun_name, casadi_codegen_opts) - - fun_name = model_name + '_gnsf_phi_jac_y_uhat' - phi_jac_y_uhat = model.phi_jac_y_uhat - phi_jac_y_uhat_ = ca.Function(fun_name, [y, uhat, p], phi_jac_y_uhat(y, uhat, p)) - phi_jac_y_uhat_.generate(fun_name, casadi_codegen_opts) - - fun_name = model_name + '_gnsf_f_lo_fun_jac_x1k1uz' - f_lo_fun_jac_x1k1uz = model.f_lo_fun_jac_x1k1uz - f_lo_fun_jac_x1k1uz_eval = f_lo_fun_jac_x1k1uz(x1, x1dot, z1, u, p) - - # avoid codegeneration issue - if not isinstance(f_lo_fun_jac_x1k1uz_eval, tuple) and is_empty(f_lo_fun_jac_x1k1uz_eval): - f_lo_fun_jac_x1k1uz_eval = [empty_var] - - f_lo_fun_jac_x1k1uz_ = ca.Function(fun_name, [x1, x1dot, z1, u, p], - f_lo_fun_jac_x1k1uz_eval) - f_lo_fun_jac_x1k1uz_.generate(fun_name, casadi_codegen_opts) - - fun_name = model_name + '_gnsf_get_matrices_fun' - get_matrices_fun_ = ca.Function(fun_name, [dummy], get_matrices_fun(1)) - get_matrices_fun_.generate(fun_name, casadi_codegen_opts) - - # remove fields for json dump - del model.phi_fun - del model.phi_fun_jac_y - del model.phi_jac_y_uhat - del model.f_lo_fun_jac_x1k1uz - del model.get_matrices_fun - - os.chdir(cwd) - - return - - -################ -# Cost -################ - -def generate_c_code_external_cost(model, stage_type, opts): - - casadi_codegen_opts = dict(mex=False, casadi_int='int', casadi_real='double') - - x = model.x - p = model.p - u = model.u - z = model.z - symbol = get_casadi_symbol(x) - - if stage_type == 'terminal': - suffix_name = "_cost_ext_cost_e_fun" - suffix_name_hess = "_cost_ext_cost_e_fun_jac_hess" - suffix_name_jac = "_cost_ext_cost_e_fun_jac" - ext_cost = model.cost_expr_ext_cost_e - custom_hess = model.cost_expr_ext_cost_custom_hess_e - # Last stage cannot depend on u and z - u = symbol("u", 0, 0) - z = symbol("z", 0, 0) - - elif stage_type == 'path': - suffix_name = "_cost_ext_cost_fun" - suffix_name_hess = "_cost_ext_cost_fun_jac_hess" - suffix_name_jac = "_cost_ext_cost_fun_jac" - ext_cost = model.cost_expr_ext_cost - custom_hess = model.cost_expr_ext_cost_custom_hess - - elif stage_type == 'initial': - suffix_name = "_cost_ext_cost_0_fun" - suffix_name_hess = "_cost_ext_cost_0_fun_jac_hess" - suffix_name_jac = "_cost_ext_cost_0_fun_jac" - ext_cost = model.cost_expr_ext_cost_0 - custom_hess = model.cost_expr_ext_cost_custom_hess_0 - - nunx = x.shape[0] + u.shape[0] - - # set up functions to be exported - fun_name = model.name + suffix_name - fun_name_hess = model.name + suffix_name_hess - fun_name_jac = model.name + suffix_name_jac - - # generate expression for full gradient and Hessian - hess_uxz, grad_uxz = ca.hessian(ext_cost, ca.vertcat(u, x, z)) - - hess_ux = hess_uxz[:nunx, :nunx] - hess_z = hess_uxz[nunx:, nunx:] - hess_z_ux = hess_uxz[nunx:, :nunx] - - if custom_hess is not None: - hess_ux = custom_hess - - ext_cost_fun = ca.Function(fun_name, [x, u, z, p], [ext_cost]) - - ext_cost_fun_jac_hess = ca.Function( - fun_name_hess, [x, u, z, p], [ext_cost, grad_uxz, hess_ux, hess_z, hess_z_ux] - ) - ext_cost_fun_jac = ca.Function( - fun_name_jac, [x, u, z, p], [ext_cost, grad_uxz] - ) - - # change directory - cwd = os.getcwd() - cost_dir = os.path.abspath(os.path.join(opts["code_export_directory"], f'{model.name}_cost')) - if not os.path.exists(cost_dir): - os.makedirs(cost_dir) - os.chdir(cost_dir) - - ext_cost_fun.generate(fun_name, casadi_codegen_opts) - ext_cost_fun_jac_hess.generate(fun_name_hess, casadi_codegen_opts) - ext_cost_fun_jac.generate(fun_name_jac, casadi_codegen_opts) - - os.chdir(cwd) - return - - -def generate_c_code_nls_cost( model, cost_name, stage_type, opts ): - - casadi_codegen_opts = dict(mex=False, casadi_int='int', casadi_real='double') - - x = model.x - z = model.z - p = model.p - u = model.u - - symbol = get_casadi_symbol(x) - - if stage_type == 'terminal': - middle_name = '_cost_y_e' - u = symbol('u', 0, 0) - y_expr = model.cost_y_expr_e - - elif stage_type == 'initial': - middle_name = '_cost_y_0' - y_expr = model.cost_y_expr_0 - - elif stage_type == 'path': - middle_name = '_cost_y' - y_expr = model.cost_y_expr - - # change directory - cwd = os.getcwd() - cost_dir = os.path.abspath(os.path.join(opts["code_export_directory"], f'{model.name}_cost')) - if not os.path.exists(cost_dir): - os.makedirs(cost_dir) - os.chdir(cost_dir) - - # set up expressions - cost_jac_expr = ca.transpose(ca.jacobian(y_expr, ca.vertcat(u, x))) - dy_dz = ca.jacobian(y_expr, z) - ny = casadi_length(y_expr) - - y = symbol('y', ny, 1) - - y_adj = ca.jtimes(y_expr, ca.vertcat(u, x), y, True) - y_hess = ca.jacobian(y_adj, ca.vertcat(u, x)) - - ## generate C code - suffix_name = '_fun' - fun_name = cost_name + middle_name + suffix_name - y_fun = ca.Function( fun_name, [x, u, z, p], [ y_expr ]) - y_fun.generate( fun_name, casadi_codegen_opts ) - - suffix_name = '_fun_jac_ut_xt' - fun_name = cost_name + middle_name + suffix_name - y_fun_jac_ut_xt = ca.Function(fun_name, [x, u, z, p], [ y_expr, cost_jac_expr, dy_dz ]) - y_fun_jac_ut_xt.generate( fun_name, casadi_codegen_opts ) - - suffix_name = '_hess' - fun_name = cost_name + middle_name + suffix_name - y_hess = ca.Function(fun_name, [x, u, z, y, p], [ y_hess ]) - y_hess.generate( fun_name, casadi_codegen_opts ) - - os.chdir(cwd) - - return - - - -def generate_c_code_conl_cost(model, cost_name, stage_type, opts): - - casadi_codegen_opts = dict(mex=False, casadi_int='int', casadi_real='double') - - x = model.x - z = model.z - p = model.p - - symbol = get_casadi_symbol(x) - - if stage_type == 'terminal': - u = symbol('u', 0, 0) - - yref = model.cost_r_in_psi_expr_e - inner_expr = model.cost_y_expr_e - yref - outer_expr = model.cost_psi_expr_e - res_expr = model.cost_r_in_psi_expr_e - - suffix_name_fun = '_conl_cost_e_fun' - suffix_name_fun_jac_hess = '_conl_cost_e_fun_jac_hess' - - custom_hess = model.cost_conl_custom_outer_hess_e - - elif stage_type == 'initial': - u = model.u - - yref = model.cost_r_in_psi_expr_0 - inner_expr = model.cost_y_expr_0 - yref - outer_expr = model.cost_psi_expr_0 - res_expr = model.cost_r_in_psi_expr_0 - - suffix_name_fun = '_conl_cost_0_fun' - suffix_name_fun_jac_hess = '_conl_cost_0_fun_jac_hess' - - custom_hess = model.cost_conl_custom_outer_hess_0 - - elif stage_type == 'path': - u = model.u - - yref = model.cost_r_in_psi_expr - inner_expr = model.cost_y_expr - yref - outer_expr = model.cost_psi_expr - res_expr = model.cost_r_in_psi_expr - - suffix_name_fun = '_conl_cost_fun' - suffix_name_fun_jac_hess = '_conl_cost_fun_jac_hess' - - custom_hess = model.cost_conl_custom_outer_hess - - # set up function names - fun_name_cost_fun = model.name + suffix_name_fun - fun_name_cost_fun_jac_hess = model.name + suffix_name_fun_jac_hess - - # set up functions to be exported - outer_loss_fun = ca.Function('psi', [res_expr, p], [outer_expr]) - cost_expr = outer_loss_fun(inner_expr, p) - - outer_loss_grad_fun = ca.Function('outer_loss_grad', [res_expr, p], [ca.jacobian(outer_expr, res_expr).T]) - - if custom_hess is None: - outer_hess_fun = ca.Function('inner_hess', [res_expr, p], [ca.hessian(outer_loss_fun(res_expr, p), res_expr)[0]]) - else: - outer_hess_fun = ca.Function('inner_hess', [res_expr, p], [custom_hess]) - - Jt_ux_expr = ca.jacobian(inner_expr, ca.vertcat(u, x)).T - Jt_z_expr = ca.jacobian(inner_expr, z).T - - cost_fun = ca.Function( - fun_name_cost_fun, - [x, u, z, yref, p], - [cost_expr]) - - cost_fun_jac_hess = ca.Function( - fun_name_cost_fun_jac_hess, - [x, u, z, yref, p], - [cost_expr, outer_loss_grad_fun(inner_expr, p), Jt_ux_expr, Jt_z_expr, outer_hess_fun(inner_expr, p)] - ) - # change directory - cwd = os.getcwd() - cost_dir = os.path.abspath(os.path.join(opts["code_export_directory"], f'{model.name}_cost')) - if not os.path.exists(cost_dir): - os.makedirs(cost_dir) - os.chdir(cost_dir) - - # generate C code - cost_fun.generate(fun_name_cost_fun, casadi_codegen_opts) - cost_fun_jac_hess.generate(fun_name_cost_fun_jac_hess, casadi_codegen_opts) - - os.chdir(cwd) - - return - - -################ -# Constraints -################ -def generate_c_code_constraint( model, con_name, is_terminal, opts ): - - casadi_codegen_opts = dict(mex=False, casadi_int='int', casadi_real='double') - - # load constraint variables and expression - x = model.x - p = model.p - - symbol = get_casadi_symbol(x) - - if is_terminal: - con_h_expr = model.con_h_expr_e - con_phi_expr = model.con_phi_expr_e - # create dummy u, z - u = symbol('u', 0, 0) - z = symbol('z', 0, 0) - else: - con_h_expr = model.con_h_expr - con_phi_expr = model.con_phi_expr - u = model.u - z = model.z - - if (not is_empty(con_h_expr)) and (not is_empty(con_phi_expr)): - raise Exception("acados: you can either have constraint_h, or constraint_phi, not both.") - - if (is_empty(con_h_expr) and is_empty(con_phi_expr)): - # both empty -> nothing to generate - return - - if is_empty(con_h_expr): - constr_type = 'BGP' - else: - constr_type = 'BGH' - - if is_empty(p): - p = symbol('p', 0, 0) - - if is_empty(z): - z = symbol('z', 0, 0) - - if not (is_empty(con_h_expr)) and opts['generate_hess']: - # multipliers for hessian - nh = casadi_length(con_h_expr) - lam_h = symbol('lam_h', nh, 1) - - # set up & change directory - cwd = os.getcwd() - constraints_dir = os.path.abspath(os.path.join(opts["code_export_directory"], f'{model.name}_constraints')) - if not os.path.exists(constraints_dir): - os.makedirs(constraints_dir) - os.chdir(constraints_dir) - - # export casadi functions - if constr_type == 'BGH': - if is_terminal: - fun_name = con_name + '_constr_h_e_fun_jac_uxt_zt' - else: - fun_name = con_name + '_constr_h_fun_jac_uxt_zt' - - jac_ux_t = ca.transpose(ca.jacobian(con_h_expr, ca.vertcat(u,x))) - jac_z_t = ca.jacobian(con_h_expr, z) - constraint_fun_jac_tran = ca.Function(fun_name, [x, u, z, p], \ - [con_h_expr, jac_ux_t, jac_z_t]) - - constraint_fun_jac_tran.generate(fun_name, casadi_codegen_opts) - if opts['generate_hess']: - - if is_terminal: - fun_name = con_name + '_constr_h_e_fun_jac_uxt_zt_hess' - else: - fun_name = con_name + '_constr_h_fun_jac_uxt_zt_hess' - - # adjoint - adj_ux = ca.jtimes(con_h_expr, ca.vertcat(u, x), lam_h, True) - # hessian - hess_ux = ca.jacobian(adj_ux, ca.vertcat(u, x)) - - adj_z = ca.jtimes(con_h_expr, z, lam_h, True) - hess_z = ca.jacobian(adj_z, z) - - # set up functions - constraint_fun_jac_tran_hess = \ - ca.Function(fun_name, [x, u, lam_h, z, p], \ - [con_h_expr, jac_ux_t, hess_ux, jac_z_t, hess_z]) - - # generate C code - constraint_fun_jac_tran_hess.generate(fun_name, casadi_codegen_opts) - - if is_terminal: - fun_name = con_name + '_constr_h_e_fun' - else: - fun_name = con_name + '_constr_h_fun' - h_fun = ca.Function(fun_name, [x, u, z, p], [con_h_expr]) - h_fun.generate(fun_name, casadi_codegen_opts) - - else: # BGP constraint - if is_terminal: - fun_name = con_name + '_phi_e_constraint' - r = model.con_r_in_phi_e - con_r_expr = model.con_r_expr_e - else: - fun_name = con_name + '_phi_constraint' - r = model.con_r_in_phi - con_r_expr = model.con_r_expr - - nphi = casadi_length(con_phi_expr) - con_phi_expr_x_u_z = ca.substitute(con_phi_expr, r, con_r_expr) - phi_jac_u = ca.jacobian(con_phi_expr_x_u_z, u) - phi_jac_x = ca.jacobian(con_phi_expr_x_u_z, x) - phi_jac_z = ca.jacobian(con_phi_expr_x_u_z, z) - - hess = ca.hessian(con_phi_expr[0], r)[0] - for i in range(1, nphi): - hess = ca.vertcat(hess, ca.hessian(con_phi_expr[i], r)[0]) - - r_jac_u = ca.jacobian(con_r_expr, u) - r_jac_x = ca.jacobian(con_r_expr, x) - - constraint_phi = \ - ca.Function(fun_name, [x, u, z, p], \ - [con_phi_expr_x_u_z, \ - ca.vertcat(ca.transpose(phi_jac_u), ca.transpose(phi_jac_x)), \ - ca.transpose(phi_jac_z), \ - hess, - ca.vertcat(ca.transpose(r_jac_u), ca.transpose(r_jac_x))]) - - constraint_phi.generate(fun_name, casadi_codegen_opts) - - # change directory back - os.chdir(cwd) - - return - diff --git a/third_party/acados/acados_template/custom_update_templates/custom_update_function_zoro_template.in.c b/third_party/acados/acados_template/custom_update_templates/custom_update_function_zoro_template.in.c deleted file mode 100644 index b39ff2e23b..0000000000 --- a/third_party/acados/acados_template/custom_update_templates/custom_update_function_zoro_template.in.c +++ /dev/null @@ -1,819 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - -// This is a template based custom_update function -#include -#include -#include -#include - -#include "custom_update_function.h" -#include "acados_solver_{{ model.name }}.h" -#include "acados_c/ocp_nlp_interface.h" -#include "acados/utils/mem.h" - -#include "blasfeo/include/blasfeo_d_aux_ext_dep.h" -#include "blasfeo/include/blasfeo_d_blasfeo_api.h" - - -typedef struct custom_memory -{ - // covariance matrics - struct blasfeo_dmat *uncertainty_matrix_buffer; // shape = (N+1, nx, nx) - // covariance matrix of the additive disturbance - struct blasfeo_dmat W_mat; // shape = (nw, nw) - struct blasfeo_dmat unc_jac_G_mat; // shape = (nx, nw) - struct blasfeo_dmat temp_GW_mat; // shape = (nx, nw) - struct blasfeo_dmat GWG_mat; // shape = (nx, nx) - // sensitivity matrices - struct blasfeo_dmat A_mat; // shape = (nx, nx) - struct blasfeo_dmat B_mat; // shape = (nx, nu) - // matrix in linear constraints - struct blasfeo_dmat Cg_mat; // shape = (ng, nx) - struct blasfeo_dmat Dg_mat; // shape = (ng, nu) - struct blasfeo_dmat Cg_e_mat; // shape = (ng_e, nx) - struct blasfeo_dmat dummy_Dgh_e_mat; // shape = (ngh_e_max, nu) - // matrix in nonlinear constraints - struct blasfeo_dmat Ch_mat; // shape = (nh, nx) - struct blasfeo_dmat Dh_mat; // shape = (nh, nu) - struct blasfeo_dmat Ch_e_mat; // shape = (nh_e, nx) - // feedback gain matrix - struct blasfeo_dmat K_mat; // shape = (nu, nx) - // AK = A - B@K - struct blasfeo_dmat AK_mat; // shape = (nx, nx) - // A@P_k - struct blasfeo_dmat temp_AP_mat; // shape = (nx, nx) - // K@P_k, K@P_k@K^T - struct blasfeo_dmat temp_KP_mat; // shape = (nu, nx) - struct blasfeo_dmat temp_KPK_mat; // shape = (nu, nu) - // C + D @ K, (C + D @ K) @ P_k - struct blasfeo_dmat temp_CaDK_mat; // shape = (ngh_me_max, nx) - struct blasfeo_dmat temp_CaDKmP_mat; // shape = (ngh_me_max, nx) - struct blasfeo_dmat temp_beta_mat; // shape = (ngh_me_max, ngh_me_max) - - double *d_A_mat; // shape = (nx, nx) - double *d_B_mat; // shape = (nx, nu) - double *d_Cg_mat; // shape = (ng, nx) - double *d_Dg_mat; // shape = (ng, nu) - double *d_Cg_e_mat; // shape = (ng_e, nx) - double *d_Cgh_mat; // shape = (ng+nh, nx) - double *d_Dgh_mat; // shape = (ng+nh, nu) - double *d_Cgh_e_mat; // shape = (ng_e+nh_e, nx) - double *d_state_vec; - // upper and lower bounds on state variables - double *d_lbx; // shape = (nbx,) - double *d_ubx; // shape = (nbx,) - double *d_lbx_e; // shape = (nbx_e,) - double *d_ubx_e; // shape = (nbx_e,) - // tightened upper and lower bounds on state variables - double *d_lbx_tightened; // shape = (nbx,) - double *d_ubx_tightened; // shape = (nbx,) - double *d_lbx_e_tightened; // shape = (nbx_e,) - double *d_ubx_e_tightened; // shape = (nbx_e,) - // upper and lower bounds on control inputs - double *d_lbu; // shape = (nbu,) - double *d_ubu; // shape = (nbu,) - // tightened upper and lower bounds on control inputs - double *d_lbu_tightened; // shape = (nbu,) - double *d_ubu_tightened; // shape = (nbu,) - // upper and lower bounds on polytopic constraints - double *d_lg; // shape = (ng,) - double *d_ug; // shape = (ng,) - double *d_lg_e; // shape = (ng_e,) - double *d_ug_e; // shape = (ng_e,) - // tightened lower bounds on polytopic constraints - double *d_lg_tightened; // shape = (ng,) - double *d_ug_tightened; // shape = (ng,) - double *d_lg_e_tightened; // shape = (ng_e,) - double *d_ug_e_tightened; // shape = (ng_e,) - // upper and lower bounds on nonlinear constraints - double *d_lh; // shape = (nh,) - double *d_uh; // shape = (nh,) - double *d_lh_e; // shape = (nh_e,) - double *d_uh_e; // shape = (nh_e,) - // tightened upper and lower bounds on nonlinear constraints - double *d_lh_tightened; // shape = (nh,) - double *d_uh_tightened; // shape = (nh,) - double *d_lh_e_tightened; // shape = (nh_e,) - double *d_uh_e_tightened; // shape = (nh_e,) - - int *idxbx; // shape = (nbx,) - int *idxbu; // shape = (nbu,) - int *idxbx_e; // shape = (nbx_e,) - - void *raw_memory; // Pointer to allocated memory, to be used for freeing -} custom_memory; - -static int int_max(int num1, int num2) -{ - return (num1 > num2 ) ? num1 : num2; -} - - -static int custom_memory_calculate_size(ocp_nlp_config *nlp_config, ocp_nlp_dims *nlp_dims) -{ - int N = nlp_dims->N; - int nx = {{ dims.nx }}; - int nu = {{ dims.nu }}; - int nw = {{ zoro_description.nw }}; - - int ng = {{ dims.ng }}; - int nh = {{ dims.nh }}; - int nbx = {{ dims.nbx }}; - int nbu = {{ dims.nbu }}; - - int ng_e = {{ dims.ng_e }}; - int nh_e = {{ dims.nh_e }}; - int ngh_e_max = int_max(ng_e, nh_e); - int ngh_me_max = int_max(ngh_e_max, int_max(ng, nh)); - int nbx_e = {{ dims.nbx_e }}; - - assert({{zoro_description.nlbx_t}} <= nbx); - assert({{zoro_description.nubx_t}} <= nbx); - assert({{zoro_description.nlbu_t}} <= nbu); - assert({{zoro_description.nubu_t}} <= nbu); - assert({{zoro_description.nlg_t}} <= ng); - assert({{zoro_description.nug_t}} <= ng); - assert({{zoro_description.nlh_t}} <= nh); - assert({{zoro_description.nuh_t}} <= nh); - assert({{zoro_description.nlbx_e_t}} <= nbx_e); - assert({{zoro_description.nubx_e_t}} <= nbx_e); - assert({{zoro_description.nlg_e_t}} <= ng_e); - assert({{zoro_description.nug_e_t}} <= ng_e); - assert({{zoro_description.nlh_e_t}} <= nh_e); - assert({{zoro_description.nuh_e_t}} <= nh_e); - - acados_size_t size = sizeof(custom_memory); - size += nbx * sizeof(int); - /* blasfeo structs */ - size += (N + 1) * sizeof(struct blasfeo_dmat); - /* blasfeo mem: mat */ - size += (N + 1) * blasfeo_memsize_dmat(nx, nx); // uncertainty_matrix_buffer - size += blasfeo_memsize_dmat(nw, nw); // W_mat - size += 2 * blasfeo_memsize_dmat(nx, nw); // unc_jac_G_mat, temp_GW_mat - size += 4 * blasfeo_memsize_dmat(nx, nx); // GWG_mat, A_mat, AK_mat, temp_AP_mat - size += blasfeo_memsize_dmat(nx, nu); // B_mat - size += 2 * blasfeo_memsize_dmat(nu, nx); // K_mat, temp_KP_mat - size += blasfeo_memsize_dmat(nu, nu); // temp_KPK_mat - size += blasfeo_memsize_dmat(ng, nx); // Cg_mat - size += blasfeo_memsize_dmat(ng, nu); // Dg_mat - size += blasfeo_memsize_dmat(ng_e, nx); // Cg_e_mat - size += blasfeo_memsize_dmat(ngh_e_max, nu); // dummy_Dgh_e_mat - size += blasfeo_memsize_dmat(nh, nx); // Ch_mat - size += blasfeo_memsize_dmat(nh, nu); // Dh_mat - size += blasfeo_memsize_dmat(nh_e, nx); // Ch_e_mat - size += 2 * blasfeo_memsize_dmat(ngh_me_max, nx); // temp_CaDK_mat, temp_CaDKmP_mat - size += blasfeo_memsize_dmat(ngh_me_max, ngh_me_max); // temp_beta_mat - /* blasfeo mem: vec */ - /* Arrays */ - size += nx*nx *sizeof(double); // d_A_mat - size += nx*nu *sizeof(double); // d_B_mat - size += (ng + ng_e) * nx * sizeof(double); // d_Cg_mat, d_Cg_e_mat - size += (ng) * nu * sizeof(double); // d_Dg_mat - size += (nh + nh_e + ng + ng_e) * nx * sizeof(double); // d_Cgh_mat, d_Cgh_e_mat - size += (nh + ng) * nu * sizeof(double); // d_Dgh_mat - // d_state_vec - size += nx *sizeof(double); - // constraints and tightened constraints - size += 4 * (nbx + nbu + ng + nh)*sizeof(double); - size += 4 * (nbx_e + ng_e + nh_e)*sizeof(double); - size += (nbx + nbu + nbx_e)*sizeof(int); // idxbx, idxbu, idxbx_e - - size += 1 * 8; // initial alignment - make_int_multiple_of(64, &size); - size += 1 * 64; - - return size; -} - - -static custom_memory *custom_memory_assign(ocp_nlp_config *nlp_config, ocp_nlp_dims *nlp_dims, void *raw_memory) -{ - int N = nlp_dims->N; - int nx = {{ dims.nx }}; - int nu = {{ dims.nu }}; - int nw = {{ zoro_description.nw }}; - - int ng = {{ dims.ng }}; - int nh = {{ dims.nh }}; - int nbx = {{ dims.nbx }}; - int nbu = {{ dims.nbu }}; - - int ng_e = {{ dims.ng_e }}; - int nh_e = {{ dims.nh_e }}; - int ngh_e_max = int_max(ng_e, nh_e); - int ngh_me_max = int_max(ngh_e_max, int_max(ng, nh)); - int nbx_e = {{ dims.nbx_e }}; - - char *c_ptr = (char *) raw_memory; - custom_memory *mem = (custom_memory *) c_ptr; - c_ptr += sizeof(custom_memory); - - align_char_to(8, &c_ptr); - assign_and_advance_blasfeo_dmat_structs(N+1, &mem->uncertainty_matrix_buffer, &c_ptr); - - align_char_to(64, &c_ptr); - - for (int ii = 0; ii <= N; ii++) - { - assign_and_advance_blasfeo_dmat_mem(nx, nx, &mem->uncertainty_matrix_buffer[ii], &c_ptr); - } - // Disturbance Dynamics - assign_and_advance_blasfeo_dmat_mem(nw, nw, &mem->W_mat, &c_ptr); - assign_and_advance_blasfeo_dmat_mem(nx, nw, &mem->unc_jac_G_mat, &c_ptr); - assign_and_advance_blasfeo_dmat_mem(nx, nw, &mem->temp_GW_mat, &c_ptr); - assign_and_advance_blasfeo_dmat_mem(nx, nx, &mem->GWG_mat, &c_ptr); - // System Dynamics - assign_and_advance_blasfeo_dmat_mem(nx, nx, &mem->A_mat, &c_ptr); - assign_and_advance_blasfeo_dmat_mem(nx, nu, &mem->B_mat, &c_ptr); - assign_and_advance_blasfeo_dmat_mem(ng, nx, &mem->Cg_mat, &c_ptr); - assign_and_advance_blasfeo_dmat_mem(ng, nu, &mem->Dg_mat, &c_ptr); - assign_and_advance_blasfeo_dmat_mem(ng_e, nx, &mem->Cg_e_mat, &c_ptr); - assign_and_advance_blasfeo_dmat_mem(ngh_e_max, nu, &mem->dummy_Dgh_e_mat, &c_ptr); - assign_and_advance_blasfeo_dmat_mem(nh, nx, &mem->Ch_mat, &c_ptr); - assign_and_advance_blasfeo_dmat_mem(nh, nu, &mem->Dh_mat, &c_ptr); - assign_and_advance_blasfeo_dmat_mem(nh_e, nx, &mem->Ch_e_mat, &c_ptr); - assign_and_advance_blasfeo_dmat_mem(nu, nx, &mem->K_mat, &c_ptr); - assign_and_advance_blasfeo_dmat_mem(nx, nx, &mem->AK_mat, &c_ptr); - assign_and_advance_blasfeo_dmat_mem(nx, nx, &mem->temp_AP_mat, &c_ptr); - assign_and_advance_blasfeo_dmat_mem(nu, nx, &mem->temp_KP_mat, &c_ptr); - assign_and_advance_blasfeo_dmat_mem(nu, nu, &mem->temp_KPK_mat, &c_ptr); - assign_and_advance_blasfeo_dmat_mem(ngh_me_max, nx, &mem->temp_CaDK_mat, &c_ptr); - assign_and_advance_blasfeo_dmat_mem(ngh_me_max, nx, &mem->temp_CaDKmP_mat, &c_ptr); - assign_and_advance_blasfeo_dmat_mem(ngh_me_max, ngh_me_max, &mem->temp_beta_mat, &c_ptr); - - assign_and_advance_double(nx*nx, &mem->d_A_mat, &c_ptr); - assign_and_advance_double(nx*nu, &mem->d_B_mat, &c_ptr); - assign_and_advance_double(ng*nx, &mem->d_Cg_mat, &c_ptr); - assign_and_advance_double(ng*nu, &mem->d_Dg_mat, &c_ptr); - assign_and_advance_double(ng_e*nx, &mem->d_Cg_e_mat, &c_ptr); - assign_and_advance_double((ng + nh)*nx, &mem->d_Cgh_mat, &c_ptr); - assign_and_advance_double((ng + nh)*nu, &mem->d_Dgh_mat, &c_ptr); - assign_and_advance_double((ng_e + nh_e)*nx, &mem->d_Cgh_e_mat, &c_ptr); - assign_and_advance_double(nx, &mem->d_state_vec, &c_ptr); - assign_and_advance_double(nbx, &mem->d_lbx, &c_ptr); - assign_and_advance_double(nbx, &mem->d_ubx, &c_ptr); - assign_and_advance_double(nbx_e, &mem->d_lbx_e, &c_ptr); - assign_and_advance_double(nbx_e, &mem->d_ubx_e, &c_ptr); - assign_and_advance_double(nbx, &mem->d_lbx_tightened, &c_ptr); - assign_and_advance_double(nbx, &mem->d_ubx_tightened, &c_ptr); - assign_and_advance_double(nbx_e, &mem->d_lbx_e_tightened, &c_ptr); - assign_and_advance_double(nbx_e, &mem->d_ubx_e_tightened, &c_ptr); - assign_and_advance_double(nbu, &mem->d_lbu, &c_ptr); - assign_and_advance_double(nbu, &mem->d_ubu, &c_ptr); - assign_and_advance_double(nbu, &mem->d_lbu_tightened, &c_ptr); - assign_and_advance_double(nbu, &mem->d_ubu_tightened, &c_ptr); - assign_and_advance_double(ng, &mem->d_lg, &c_ptr); - assign_and_advance_double(ng, &mem->d_ug, &c_ptr); - assign_and_advance_double(ng_e, &mem->d_lg_e, &c_ptr); - assign_and_advance_double(ng_e, &mem->d_ug_e, &c_ptr); - assign_and_advance_double(ng, &mem->d_lg_tightened, &c_ptr); - assign_and_advance_double(ng, &mem->d_ug_tightened, &c_ptr); - assign_and_advance_double(ng_e, &mem->d_lg_e_tightened, &c_ptr); - assign_and_advance_double(ng_e, &mem->d_ug_e_tightened, &c_ptr); - assign_and_advance_double(nh, &mem->d_lh, &c_ptr); - assign_and_advance_double(nh, &mem->d_uh, &c_ptr); - assign_and_advance_double(nh_e, &mem->d_lh_e, &c_ptr); - assign_and_advance_double(nh_e, &mem->d_uh_e, &c_ptr); - assign_and_advance_double(nh, &mem->d_lh_tightened, &c_ptr); - assign_and_advance_double(nh, &mem->d_uh_tightened, &c_ptr); - assign_and_advance_double(nh_e, &mem->d_lh_e_tightened, &c_ptr); - assign_and_advance_double(nh_e, &mem->d_uh_e_tightened, &c_ptr); - - assign_and_advance_int(nbx, &mem->idxbx, &c_ptr); - assign_and_advance_int(nbu, &mem->idxbu, &c_ptr); - assign_and_advance_int(nbx_e, &mem->idxbx_e, &c_ptr); - - assert((char *) raw_memory + custom_memory_calculate_size(nlp_config, nlp_dims) >= c_ptr); - mem->raw_memory = raw_memory; - - return mem; -} - - - -static void *custom_memory_create({{ model.name }}_solver_capsule* capsule) -{ - printf("\nin custom_memory_create_function\n"); - - ocp_nlp_dims *nlp_dims = {{ model.name }}_acados_get_nlp_dims(capsule); - ocp_nlp_config *nlp_config = {{ model.name }}_acados_get_nlp_config(capsule); - acados_size_t bytes = custom_memory_calculate_size(nlp_config, nlp_dims); - - void *ptr = acados_calloc(1, bytes); - - custom_memory *custom_mem = custom_memory_assign(nlp_config, nlp_dims, ptr); - custom_mem->raw_memory = ptr; - - return custom_mem; -} - - -static void custom_val_init_function(ocp_nlp_dims *nlp_dims, ocp_nlp_in *nlp_in, ocp_nlp_solver *nlp_solver, custom_memory *custom_mem) -{ - int N = nlp_dims->N; - int nx = {{ dims.nx }}; - int nu = {{ dims.nu }}; - int nw = {{ zoro_description.nw }}; - - int ng = {{ dims.ng }}; - int nh = {{ dims.nh }}; - int nbx = {{ dims.nbx }}; - int nbu = {{ dims.nbu }}; - - int ng_e = {{ dims.ng_e }}; - int nh_e = {{ dims.nh_e }}; - int ngh_e_max = int_max(ng_e, nh_e); - int nbx_e = {{ dims.nbx_e }}; - - /* Get the state constraint bounds */ - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "idxbx", custom_mem->idxbx); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, N, "idxbx", custom_mem->idxbx_e); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "lbx", custom_mem->d_lbx); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "ubx", custom_mem->d_ubx); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, N, "lbx", custom_mem->d_lbx_e); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, N, "ubx", custom_mem->d_ubx_e); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "idxbu", custom_mem->idxbu); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "lbu", custom_mem->d_lbu); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "ubu", custom_mem->d_ubu); - // Get the Jacobians and the bounds of the linear constraints - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "lg", custom_mem->d_lg); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "ug", custom_mem->d_ug); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, N, "lg", custom_mem->d_lg_e); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, N, "ug", custom_mem->d_ug_e); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "C", custom_mem->d_Cg_mat); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "D", custom_mem->d_Dg_mat); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, N, "C", custom_mem->d_Cg_e_mat); - blasfeo_pack_dmat(ng, nx, custom_mem->d_Cg_mat, ng, &custom_mem->Cg_mat, 0, 0); - blasfeo_pack_dmat(ng, nu, custom_mem->d_Dg_mat, ng, &custom_mem->Dg_mat, 0, 0); - blasfeo_pack_dmat(ng_e, nx, custom_mem->d_Cg_e_mat, ng_e, &custom_mem->Cg_e_mat, 0, 0); - blasfeo_dgese(ngh_e_max, nu, 0., &custom_mem->dummy_Dgh_e_mat, 0, 0); //fill with zeros - // NOTE: fixed lower and upper bounds of nonlinear constraints - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "lh", custom_mem->d_lh); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "uh", custom_mem->d_uh); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, N, "lh", custom_mem->d_lh_e); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, N, "uh", custom_mem->d_uh_e); - - /* Initilize tightened constraints*/ - // NOTE: tightened constraints are only initialized once - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "lbx", custom_mem->d_lbx_tightened); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "ubx", custom_mem->d_ubx_tightened); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, N, "lbx", custom_mem->d_lbx_e_tightened); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, N, "ubx", custom_mem->d_ubx_e_tightened); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "lbu", custom_mem->d_lbu_tightened); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "ubu", custom_mem->d_ubu_tightened); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "lg", custom_mem->d_lg_tightened); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "ug", custom_mem->d_ug_tightened); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, N, "lg", custom_mem->d_lg_e_tightened); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, N, "ug", custom_mem->d_ug_e_tightened); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "lh", custom_mem->d_lh_tightened); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "uh", custom_mem->d_uh_tightened); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, N, "lh", custom_mem->d_lh_e_tightened); - ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, N, "uh", custom_mem->d_uh_e_tightened); - - /* Initialize the W matrix */ - // blasfeo_dgese(nw, nw, 0., &custom_mem->W_mat, 0, 0); -{%- for ir in range(end=zoro_description.nw) %} - {%- for ic in range(end=zoro_description.nw) %} - blasfeo_dgein1({{zoro_description.W_mat[ir][ic]}}, &custom_mem->W_mat, {{ir}}, {{ic}}); - {%- endfor %} -{%- endfor %} - -{%- for ir in range(end=dims.nx) %} - {%- for ic in range(end=zoro_description.nw) %} - blasfeo_dgein1({{zoro_description.unc_jac_G_mat[ir][ic]}}, &custom_mem->unc_jac_G_mat, {{ir}}, {{ic}}); - {%- endfor %} -{%- endfor %} - - // NOTE: if G is changing this is not in init! - // temp_GW_mat = unc_jac_G_mat * W_mat - blasfeo_dgemm_nn(nx, nw, nw, 1.0, &custom_mem->unc_jac_G_mat, 0, 0, - &custom_mem->W_mat, 0, 0, 0.0, - &custom_mem->temp_GW_mat, 0, 0, &custom_mem->temp_GW_mat, 0, 0); - // GWG_mat = temp_GW_mat * unc_jac_G_mat^T - blasfeo_dgemm_nt(nx, nx, nw, 1.0, &custom_mem->temp_GW_mat, 0, 0, - &custom_mem->unc_jac_G_mat, 0, 0, 0.0, - &custom_mem->GWG_mat, 0, 0, &custom_mem->GWG_mat, 0, 0); - - /* Initialize the uncertainty_matrix_buffer[0] */ -{%- for ir in range(end=dims.nx) %} - {%- for ic in range(end=dims.nx) %} - blasfeo_dgein1({{zoro_description.P0_mat[ir][ic]}}, &custom_mem->uncertainty_matrix_buffer[0], {{ir}}, {{ic}}); - {%- endfor %} -{%- endfor %} - - /* Initialize the feedback gain matrix */ -{%- for ir in range(end=dims.nu) %} - {%- for ic in range(end=dims.nx) %} - blasfeo_dgein1({{zoro_description.fdbk_K_mat[ir][ic]}}, &custom_mem->K_mat, {{ir}}, {{ic}}); - {%- endfor %} -{%- endfor %} -} - - -int custom_update_init_function({{ model.name }}_solver_capsule* capsule) -{ - capsule->custom_update_memory = custom_memory_create(capsule); - ocp_nlp_in *nlp_in = {{ model.name }}_acados_get_nlp_in(capsule); - - ocp_nlp_dims *nlp_dims = {{ model.name }}_acados_get_nlp_dims(capsule); - ocp_nlp_solver *nlp_solver = {{ model.name }}_acados_get_nlp_solver(capsule); - custom_val_init_function(nlp_dims, nlp_in, nlp_solver, capsule->custom_update_memory); - return 1; -} - -static void compute_gh_beta(struct blasfeo_dmat* K_mat, struct blasfeo_dmat* C_mat, - struct blasfeo_dmat* D_mat, struct blasfeo_dmat* CaDK_mat, - struct blasfeo_dmat* CaDKmP_mat, struct blasfeo_dmat* beta_mat, - struct blasfeo_dmat* P_mat, - int n_cstr, int nx, int nu) -{ - // (C+DK)@P@(C^T+K^TD^T) - // CaDK_mat = C_mat + D_mat @ K_mat - blasfeo_dgemm_nn(n_cstr, nx, nu, 1.0, D_mat, 0, 0, - K_mat, 0, 0, 1.0, - C_mat, 0, 0, CaDK_mat, 0, 0); - // CaDKmP_mat = CaDK_mat @ P_mat - blasfeo_dgemm_nn(n_cstr, nx, nx, 1.0, CaDK_mat, 0, 0, - P_mat, 0, 0, 0.0, - CaDKmP_mat, 0, 0, CaDKmP_mat, 0, 0); - // beta_mat = CaDKmP_mat @ CaDK_mat^T - blasfeo_dgemm_nt(n_cstr, n_cstr, nx, 1.0, CaDKmP_mat, 0, 0, - CaDK_mat, 0, 0, 0.0, - beta_mat, 0, 0, beta_mat, 0, 0); -} - -static void compute_KPK(struct blasfeo_dmat* K_mat, struct blasfeo_dmat* temp_KP_mat, - struct blasfeo_dmat* temp_KPK_mat, struct blasfeo_dmat* P_mat, - int nx, int nu) -{ - // K @ P_k @ K^T - // temp_KP_mat = K_mat @ P_mat - blasfeo_dgemm_nn(nu, nx, nx, 1.0, K_mat, 0, 0, - P_mat, 0, 0, 0.0, - temp_KP_mat, 0, 0, temp_KP_mat, 0, 0); - // temp_KPK_mat = temp_KP_mat @ K_mat^T - blasfeo_dgemm_nt(nu, nu, nx, 1.0, temp_KP_mat, 0, 0, - K_mat, 0, 0, 0.0, - temp_KPK_mat, 0, 0, temp_KPK_mat, 0, 0); -} - -static void compute_next_P_matrix(struct blasfeo_dmat* P_mat, struct blasfeo_dmat* P_next_mat, - struct blasfeo_dmat* A_mat, struct blasfeo_dmat* B_mat, - struct blasfeo_dmat* K_mat, struct blasfeo_dmat* W_mat, - struct blasfeo_dmat* AK_mat, struct blasfeo_dmat* temp_AP_mat, int nx, int nu) -{ - // AK_mat = -B@K + A - blasfeo_dgemm_nn(nx, nx, nu, -1.0, B_mat, 0, 0, K_mat, 0, 0, - 1.0, A_mat, 0, 0, AK_mat, 0, 0); - // temp_AP_mat = AK_mat @ P_k - blasfeo_dgemm_nn(nx, nx, nx, 1.0, AK_mat, 0, 0, - P_mat, 0, 0, 0.0, - temp_AP_mat, 0, 0, temp_AP_mat, 0, 0); - // P_{k+1} = temp_AP_mat @ AK_mat^T + GWG_mat - blasfeo_dgemm_nt(nx, nx, nx, 1.0, temp_AP_mat, 0, 0, - AK_mat, 0, 0, 1.0, - W_mat, 0, 0, P_next_mat, 0, 0); -} - -static void reset_P0_matrix(ocp_nlp_dims *nlp_dims, struct blasfeo_dmat* P_mat, double* data) -{ - int nx = nlp_dims->nx[0]; - blasfeo_pack_dmat(nx, nx, data, nx, P_mat, 0, 0); -} - -static void uncertainty_propagate_and_update(ocp_nlp_solver *solver, ocp_nlp_in *nlp_in, ocp_nlp_out *nlp_out, custom_memory *custom_mem) -{ - ocp_nlp_config *nlp_config = solver->config; - ocp_nlp_dims *nlp_dims = solver->dims; - - int N = nlp_dims->N; - int nx = nlp_dims->nx[0]; - int nu = nlp_dims->nu[0]; - int nx_sqr = nx*nx; - int nbx = {{ dims.nbx }}; - int nbu = {{ dims.nbu }}; - int ng = {{ dims.ng }}; - int nh = {{ dims.nh }}; - int ng_e = {{ dims.ng_e }}; - int nh_e = {{ dims.nh_e }}; - int nbx_e = {{ dims.nbx_e }}; - double backoff_scaling_gamma = {{ zoro_description.backoff_scaling_gamma }}; - - // First Stage - // NOTE: lbx_0 and ubx_0 should not be tightened. - // NOTE: lg_0 and ug_0 are not tightened. - // NOTE: lh_0 and uh_0 are not tightened. -{%- if zoro_description.nlbu_t + zoro_description.nubu_t > 0 %} - compute_KPK(&custom_mem->K_mat, &custom_mem->temp_KP_mat, - &custom_mem->temp_KPK_mat, &(custom_mem->uncertainty_matrix_buffer[0]), nx, nu); - -{%- if zoro_description.nlbu_t > 0 %} - // backoff lbu - {%- for it in zoro_description.idx_lbu_t %} - custom_mem->d_lbu_tightened[{{it}}] - = custom_mem->d_lbu[{{it}}] - + backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->temp_KPK_mat, - custom_mem->idxbu[{{it}}],custom_mem->idxbu[{{it}}])); - {%- endfor %} - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "lbu", custom_mem->d_lbu_tightened); -{%- endif %} -{%- if zoro_description.nubu_t > 0 %} - // backoff ubu - {%- for it in zoro_description.idx_ubu_t %} - custom_mem->d_ubu_tightened[{{it}}] - = custom_mem->d_ubu[{{it}}] - - backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->temp_KPK_mat, - custom_mem->idxbu[{{it}}],custom_mem->idxbu[{{it}}])); - {%- endfor %} - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "ubu", custom_mem->d_ubu_tightened); -{%- endif %} -{%- endif %} - // Middle Stages - // constraint tightening: for next stage based on dynamics of ii stage - // P[ii+1] = (A-B@K) @ P[ii] @ (A-B@K).T + G@W@G.T - for (int ii = 0; ii < N-1; ii++) - { - // get and pack: A, B - ocp_nlp_get_at_stage(nlp_config, nlp_dims, solver, ii, "A", custom_mem->d_A_mat); - blasfeo_pack_dmat(nx, nx, custom_mem->d_A_mat, nx, &custom_mem->A_mat, 0, 0); - ocp_nlp_get_at_stage(nlp_config, nlp_dims, solver, ii, "B", custom_mem->d_B_mat); - blasfeo_pack_dmat(nx, nu, custom_mem->d_B_mat, nx, &custom_mem->B_mat, 0, 0); - - compute_next_P_matrix(&(custom_mem->uncertainty_matrix_buffer[ii]), - &(custom_mem->uncertainty_matrix_buffer[ii+1]), - &custom_mem->A_mat, &custom_mem->B_mat, - &custom_mem->K_mat, &custom_mem->GWG_mat, - &custom_mem->AK_mat, &custom_mem->temp_AP_mat, nx, nu); - - // state constraints -{%- if zoro_description.nlbx_t + zoro_description.nubx_t> 0 %} - {%- if zoro_description.nlbx_t > 0 %} - // lbx - {%- for it in zoro_description.idx_lbx_t %} - custom_mem->d_lbx_tightened[{{it}}] - = custom_mem->d_lbx[{{it}}] - + backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->uncertainty_matrix_buffer[ii+1], - custom_mem->idxbx[{{it}}],custom_mem->idxbx[{{it}}])); - {%- endfor %} - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii+1, "lbx", custom_mem->d_lbx_tightened); - {%- endif %} - {% if zoro_description.nubx_t > 0 %} - // ubx - {%- for it in zoro_description.idx_ubx_t %} - custom_mem->d_ubx_tightened[{{it}}] = custom_mem->d_ubx[{{it}}] - - backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->uncertainty_matrix_buffer[ii+1], - custom_mem->idxbx[{{it}}],custom_mem->idxbx[{{it}}])); - {%- endfor %} - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii+1, "ubx", custom_mem->d_ubx_tightened); - {%- endif %} -{%- endif %} - -{%- if zoro_description.nlbu_t + zoro_description.nubu_t > 0 %} - // input constraints - compute_KPK(&custom_mem->K_mat, &custom_mem->temp_KP_mat, - &custom_mem->temp_KPK_mat, &(custom_mem->uncertainty_matrix_buffer[ii+1]), nx, nu); - - {%- if zoro_description.nlbu_t > 0 %} - {%- for it in zoro_description.idx_lbu_t %} - custom_mem->d_lbu_tightened[{{it}}] = custom_mem->d_lbu[{{it}}] - + backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->temp_KPK_mat, - custom_mem->idxbu[{{it}}], custom_mem->idxbu[{{it}}])); - {%- endfor %} - - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii+1, "lbu", custom_mem->d_lbu_tightened); - {%- endif %} - {%- if zoro_description.nubu_t > 0 %} - {%- for it in zoro_description.idx_ubu_t %} - custom_mem->d_ubu_tightened[{{it}}] = custom_mem->d_ubu[{{it}}] - - backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->temp_KPK_mat, - custom_mem->idxbu[{{it}}], custom_mem->idxbu[{{it}}])); - {%- endfor %} - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii+1, "ubu", custom_mem->d_ubu_tightened); - {%- endif %} -{%- endif %} - -{%- if zoro_description.nlg_t + zoro_description.nug_t > 0 %} - // Linear constraints: g - compute_gh_beta(&custom_mem->K_mat, &custom_mem->Cg_mat, - &custom_mem->Dg_mat, &custom_mem->temp_CaDK_mat, - &custom_mem->temp_CaDKmP_mat, &custom_mem->temp_beta_mat, - &custom_mem->uncertainty_matrix_buffer[ii+1], ng, nx, nu); - - {%- if zoro_description.nlg_t > 0 %} - {%- for it in zoro_description.idx_lg_t %} - custom_mem->d_lg_tightened[{{it}}] - = custom_mem->d_lg[{{it}}] - + backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->temp_beta_mat, {{it}}, {{it}})); - {%- endfor %} - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii+1, "lg", custom_mem->d_lg_tightened); - {%- endif %} - {%- if zoro_description.nug_t > 0 %} - {%- for it in zoro_description.idx_ug_t %} - custom_mem->d_ug_tightened[{{it}}] - = custom_mem->d_ug[{{it}}] - - backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->temp_beta_mat, {{it}}, {{it}})); - {%- endfor %} - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii+1, "ug", custom_mem->d_ug_tightened); - {%- endif %} -{%- endif %} - - -{%- if zoro_description.nlh_t + zoro_description.nuh_t > 0 %} - // nonlinear constraints: h - // Get C_{k+1} and D_{k+1} - ocp_nlp_get_at_stage(solver->config, nlp_dims, solver, ii+1, "C", custom_mem->d_Cgh_mat); - ocp_nlp_get_at_stage(solver->config, nlp_dims, solver, ii+1, "D", custom_mem->d_Dgh_mat); - // NOTE: the d_Cgh_mat is column-major, the first ng rows are the Jacobians of the linear constraints - blasfeo_pack_dmat(nh, nx, custom_mem->d_Cgh_mat+ng, ng+nh, &custom_mem->Ch_mat, 0, 0); - blasfeo_pack_dmat(nh, nu, custom_mem->d_Dgh_mat+ng, ng+nh, &custom_mem->Dh_mat, 0, 0); - - compute_gh_beta(&custom_mem->K_mat, &custom_mem->Ch_mat, - &custom_mem->Dh_mat, &custom_mem->temp_CaDK_mat, - &custom_mem->temp_CaDKmP_mat, &custom_mem->temp_beta_mat, - &custom_mem->uncertainty_matrix_buffer[ii+1], nh, nx, nu); - - {%- if zoro_description.nlh_t > 0 %} - {%- for it in zoro_description.idx_lh_t %} - custom_mem->d_lh_tightened[{{it}}] - = custom_mem->d_lh[{{it}}] - + backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->temp_beta_mat, {{it}}, {{it}})); - {%- endfor %} - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii+1, "lh", custom_mem->d_lh_tightened); - {%- endif %} - {%- if zoro_description.nuh_t > 0 %} - {%- for it in zoro_description.idx_uh_t %} - custom_mem->d_uh_tightened[{{it}}] = custom_mem->d_uh[{{it}}] - - backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->temp_beta_mat, {{it}}, {{it}})); - {%- endfor %} - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii+1, "uh", custom_mem->d_uh_tightened); - {%- endif %} -{%- endif %} - } - - // Last stage - // get and pack: A, B - ocp_nlp_get_at_stage(nlp_config, nlp_dims, solver, N-1, "A", custom_mem->d_A_mat); - blasfeo_pack_dmat(nx, nx, custom_mem->d_A_mat, nx, &custom_mem->A_mat, 0, 0); - ocp_nlp_get_at_stage(nlp_config, nlp_dims, solver, N-1, "B", custom_mem->d_B_mat); - blasfeo_pack_dmat(nx, nu, custom_mem->d_B_mat, nx, &custom_mem->B_mat, 0, 0); - // AK_mat = -B*K + A - compute_next_P_matrix(&(custom_mem->uncertainty_matrix_buffer[N-1]), - &(custom_mem->uncertainty_matrix_buffer[N]), - &custom_mem->A_mat, &custom_mem->B_mat, - &custom_mem->K_mat, &custom_mem->GWG_mat, - &custom_mem->AK_mat, &custom_mem->temp_AP_mat, nx, nu); - - // state constraints nlbx_e_t -{%- if zoro_description.nlbx_e_t + zoro_description.nubx_e_t> 0 %} -{%- if zoro_description.nlbx_e_t > 0 %} - // lbx_e - {%- for it in zoro_description.idx_lbx_e_t %} - custom_mem->d_lbx_e_tightened[{{it}}] - = custom_mem->d_lbx_e[{{it}}] - + backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->uncertainty_matrix_buffer[N], - custom_mem->idxbx_e[{{it}}],custom_mem->idxbx_e[{{it}}])); - {%- endfor %} - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "lbx", custom_mem->d_lbx_e_tightened); -{%- endif %} -{% if zoro_description.nubx_e_t > 0 %} - // ubx_e - {%- for it in zoro_description.idx_ubx_e_t %} - custom_mem->d_ubx_e_tightened[{{it}}] = custom_mem->d_ubx_e[{{it}}] - - backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->uncertainty_matrix_buffer[N], - custom_mem->idxbx_e[{{it}}],custom_mem->idxbx_e[{{it}}])); - {%- endfor %} - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "ubx", custom_mem->d_ubx_e_tightened); -{%- endif %} -{%- endif %} - -{%- if zoro_description.nlg_e_t + zoro_description.nug_e_t > 0 %} - // Linear constraints: g - compute_gh_beta(&custom_mem->K_mat, &custom_mem->Cg_mat, - &custom_mem->dummy_Dgh_e_mat, &custom_mem->temp_CaDK_mat, - &custom_mem->temp_CaDKmP_mat, &custom_mem->temp_beta_mat, - &custom_mem->uncertainty_matrix_buffer[N], ng, nx, nu); - -{%- if zoro_description.nlg_e_t > 0 %} - {%- for it in zoro_description.idx_lg_e_t %} - custom_mem->d_lg_e_tightened[{{it}}] - = custom_mem->d_lg_e[{{it}}] - + backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->temp_beta_mat, {{it}}, {{it}})); - {%- endfor %} - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "lg", custom_mem->d_lg_e_tightened); -{%- endif %} -{%- if zoro_description.nug_e_t > 0 %} - {%- for it in zoro_description.idx_ug_e_t %} - custom_mem->d_ug_e_tightened[{{it}}] - = custom_mem->d_ug_e[{{it}}] - - backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->temp_beta_mat, {{it}}, {{it}})); - {%- endfor %} - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "ug", custom_mem->d_ug_e_tightened); -{%- endif %} -{%- endif %} - - -{%- if zoro_description.nlh_e_t + zoro_description.nuh_e_t > 0 %} - // nonlinear constraints: h - // Get C_{k+1} and D_{k+1} - ocp_nlp_get_at_stage(solver->config, nlp_dims, solver, N, "C", custom_mem->d_Cgh_mat); - // NOTE: the d_Cgh_mat is column-major, the first ng rows are the Jacobians of the linear constraints - blasfeo_pack_dmat(nh, nx, custom_mem->d_Cgh_mat+ng, ng+nh, &custom_mem->Ch_mat, 0, 0); - - compute_gh_beta(&custom_mem->K_mat, &custom_mem->Ch_mat, - &custom_mem->dummy_Dgh_e_mat, &custom_mem->temp_CaDK_mat, - &custom_mem->temp_CaDKmP_mat, &custom_mem->temp_beta_mat, - &custom_mem->uncertainty_matrix_buffer[N], nh, nx, nu); - - {%- if zoro_description.nlh_e_t > 0 %} - {%- for it in zoro_description.idx_lh_e_t %} - custom_mem->d_lh_e_tightened[{{it}}] - = custom_mem->d_lh_e[{{it}}] - + backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->temp_beta_mat, {{it}}, {{it}})); - {%- endfor %} - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "lh", custom_mem->d_lh_e_tightened); - {%- endif %} - {%- if zoro_description.nuh_e_t > 0 %} - {%- for it in zoro_description.idx_uh_e_t %} - custom_mem->d_uh_e_tightened[{{it}}] = custom_mem->d_uh_e[{{it}}] - - backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->temp_beta_mat, {{it}}, {{it}})); - {%- endfor %} - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "uh", custom_mem->d_uh_e_tightened); - {%- endif %} -{%- endif %} - -} - - -int custom_update_function({{ model.name }}_solver_capsule* capsule, double* data, int data_len) -{ - custom_memory *custom_mem = (custom_memory *) capsule->custom_update_memory; - ocp_nlp_config *nlp_config = {{ model.name }}_acados_get_nlp_config(capsule); - ocp_nlp_dims *nlp_dims = {{ model.name }}_acados_get_nlp_dims(capsule); - ocp_nlp_in *nlp_in = {{ model.name }}_acados_get_nlp_in(capsule); - ocp_nlp_out *nlp_out = {{ model.name }}_acados_get_nlp_out(capsule); - ocp_nlp_solver *nlp_solver = {{ model.name }}_acados_get_nlp_solver(capsule); - void *nlp_opts = {{ model.name }}_acados_get_nlp_opts(capsule); - - if (data_len > 0) - { - reset_P0_matrix(nlp_dims, &custom_mem->uncertainty_matrix_buffer[0], data); - } - uncertainty_propagate_and_update(nlp_solver, nlp_in, nlp_out, custom_mem); - - return 1; -} - - -int custom_update_terminate_function({{ model.name }}_solver_capsule* capsule) -{ - custom_memory *mem = capsule->custom_update_memory; - - free(mem->raw_memory); - return 1; -} - -// useful prints for debugging - -/* -printf("A_mat:\n"); -blasfeo_print_exp_dmat(nx, nx, &custom_mem->A_mat, 0, 0); -printf("B_mat:\n"); -blasfeo_print_exp_dmat(nx, nu, &custom_mem->B_mat, 0, 0); -printf("K_mat:\n"); -blasfeo_print_exp_dmat(nu, nx, &custom_mem->K_mat, 0, 0); -printf("AK_mat:\n"); -blasfeo_print_exp_dmat(nx, nx, &custom_mem->AK_mat, 0, 0); -printf("temp_AP_mat:\n"); -blasfeo_print_exp_dmat(nx, nx, &custom_mem->temp_AP_mat, 0, 0); -printf("W_mat:\n"); -blasfeo_print_exp_dmat(nx, nx, &custom_mem->W_mat, 0, 0); -printf("P_k+1:\n"); -blasfeo_print_exp_dmat(nx, nx, &(custom_mem->uncertainty_matrix_buffer[ii+1]), 0, 0);*/ \ No newline at end of file diff --git a/third_party/acados/acados_template/custom_update_templates/custom_update_function_zoro_template.in.h b/third_party/acados/acados_template/custom_update_templates/custom_update_function_zoro_template.in.h deleted file mode 100644 index 9611ea210c..0000000000 --- a/third_party/acados/acados_template/custom_update_templates/custom_update_function_zoro_template.in.h +++ /dev/null @@ -1,44 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - -#include "acados_solver_{{ model.name }}.h" - -// Called at the end of solver creation. -// This is allowed to allocate memory and store the pointer to it into capsule->custom_update_memory. -int custom_update_init_function({{ model.name }}_solver_capsule* capsule); - - -// Custom update function that can be called between solver calls -int custom_update_function({{ model.name }}_solver_capsule* capsule, double* data, int data_len); - - -// Called just before destroying the solver. -// Responsible to free allocated memory, stored at capsule->custom_update_memory. -int custom_update_terminate_function({{ model.name }}_solver_capsule* capsule); diff --git a/third_party/acados/acados_template/gnsf/__init__.py b/third_party/acados/acados_template/gnsf/__init__.py deleted file mode 100644 index 8b13789179..0000000000 --- a/third_party/acados/acados_template/gnsf/__init__.py +++ /dev/null @@ -1 +0,0 @@ - diff --git a/third_party/acados/acados_template/gnsf/check_reformulation.py b/third_party/acados/acados_template/gnsf/check_reformulation.py deleted file mode 100644 index 2bdfbbc336..0000000000 --- a/third_party/acados/acados_template/gnsf/check_reformulation.py +++ /dev/null @@ -1,216 +0,0 @@ -# -# Copyright (c) The acados authors. -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# - -from acados_template.utils import casadi_length -from casadi import * -import numpy as np - - -def check_reformulation(model, gnsf, print_info): - - ## Description: - # this function takes the implicit ODE/ index-1 DAE and a gnsf structure - # to evaluate both models at num_eval random points x0, x0dot, z0, u0 - # if for all points the relative error is <= TOL, the function will return:: - # 1, otherwise it will give an error. - - TOL = 1e-14 - num_eval = 10 - - # get dimensions - nx = gnsf["nx"] - nu = gnsf["nu"] - nz = gnsf["nz"] - nx1 = gnsf["nx1"] - nx2 = gnsf["nx2"] - nz1 = gnsf["nz1"] - nz2 = gnsf["nz2"] - n_out = gnsf["n_out"] - - # get model matrices - A = gnsf["A"] - B = gnsf["B"] - C = gnsf["C"] - E = gnsf["E"] - c = gnsf["c"] - - L_x = gnsf["L_x"] - L_xdot = gnsf["L_xdot"] - L_z = gnsf["L_z"] - L_u = gnsf["L_u"] - - A_LO = gnsf["A_LO"] - E_LO = gnsf["E_LO"] - B_LO = gnsf["B_LO"] - c_LO = gnsf["c_LO"] - - I_x1 = range(nx1) - I_x2 = range(nx1, nx) - - I_z1 = range(nz1) - I_z2 = range(nz1, nz) - - idx_perm_f = gnsf["idx_perm_f"] - - # get casadi variables - x = gnsf["x"] - xdot = gnsf["xdot"] - z = gnsf["z"] - u = gnsf["u"] - y = gnsf["y"] - uhat = gnsf["uhat"] - p = gnsf["p"] - - # create functions - impl_dae_fun = Function("impl_dae_fun", [x, xdot, u, z, p], [model.f_impl_expr]) - phi_fun = Function("phi_fun", [y, uhat, p], [gnsf["phi_expr"]]) - f_lo_fun = Function( - "f_lo_fun", [x[range(nx1)], xdot[range(nx1)], z, u, p], [gnsf["f_lo_expr"]] - ) - - # print(gnsf) - # print(gnsf["n_out"]) - - for i_check in range(num_eval): - # generate random values - x0 = np.random.rand(nx, 1) - x0dot = np.random.rand(nx, 1) - z0 = np.random.rand(nz, 1) - u0 = np.random.rand(nu, 1) - - if gnsf["ny"] > 0: - y0 = L_x @ x0[I_x1] + L_xdot @ x0dot[I_x1] + L_z @ z0[I_z1] - else: - y0 = [] - if gnsf["nuhat"] > 0: - uhat0 = L_u @ u0 - else: - uhat0 = [] - - # eval functions - p0 = np.random.rand(gnsf["np"], 1) - f_impl_val = impl_dae_fun(x0, x0dot, u0, z0, p0).full() - phi_val = phi_fun(y0, uhat0, p0) - f_lo_val = f_lo_fun(x0[I_x1], x0dot[I_x1], z0[I_z1], u0, p0) - - f_impl_val = f_impl_val[idx_perm_f] - # eval gnsf - if n_out > 0: - C_phi = C @ phi_val - else: - C_phi = np.zeros((nx1 + nz1, 1)) - try: - gnsf_val1 = ( - A @ x0[I_x1] + B @ u0 + C_phi + c - E @ vertcat(x0dot[I_x1], z0[I_z1]) - ) - # gnsf_1 = (A @ x[I_x1] + B @ u + C_phi + c - E @ vertcat(xdot[I_x1], z[I_z1])) - except: - import pdb - - pdb.set_trace() - - if nx2 > 0: # eval LOS: - gnsf_val2 = ( - A_LO @ x0[I_x2] - + B_LO @ u0 - + c_LO - + f_lo_val - - E_LO @ vertcat(x0dot[I_x2], z0[I_z2]) - ) - gnsf_val = vertcat(gnsf_val1, gnsf_val2).full() - else: - gnsf_val = gnsf_val1.full() - # compute error and check - rel_error = np.linalg.norm(f_impl_val - gnsf_val) / np.linalg.norm(f_impl_val) - - if rel_error > TOL: - print("transcription failed rel_error > TOL") - print("you are in debug mode now: import pdb; pdb.set_trace()") - abs_error = gnsf_val - f_impl_val - # T = table(f_impl_val, gnsf_val, abs_error) - # print(T) - print("abs_error:", abs_error) - # error('transcription failed rel_error > TOL') - # check = 0 - import pdb - - pdb.set_trace() - if print_info: - print(" ") - print("model reformulation checked: relative error <= TOL = ", str(TOL)) - print(" ") - check = 1 - ## helpful for debugging: - # # use in calling function and compare - # # compare f_impl(i) with gnsf_val1(i) - # - - # nx = gnsf['nx'] - # nu = gnsf['nu'] - # nz = gnsf['nz'] - # nx1 = gnsf['nx1'] - # nx2 = gnsf['nx2'] - # - # A = gnsf['A'] - # B = gnsf['B'] - # C = gnsf['C'] - # E = gnsf['E'] - # c = gnsf['c'] - # - # L_x = gnsf['L_x'] - # L_z = gnsf['L_z'] - # L_xdot = gnsf['L_xdot'] - # L_u = gnsf['L_u'] - # - # A_LO = gnsf['A_LO'] - # - # x0 = rand(nx, 1) - # x0dot = rand(nx, 1) - # z0 = rand(nz, 1) - # u0 = rand(nu, 1) - # I_x1 = range(nx1) - # I_x2 = nx1+range(nx) - # - # y0 = L_x @ x0[I_x1] + L_xdot @ x0dot[I_x1] + L_z @ z0 - # uhat0 = L_u @ u0 - # - # gnsf_val1 = (A @ x[I_x1] + B @ u + # C @ phi_current + c) - E @ [xdot[I_x1] z] - # gnsf_val1 = gnsf_val1.simplify() - # - # # gnsf_val2 = A_LO @ x[I_x2] + gnsf['f_lo_fun'](x[I_x1], xdot[I_x1], z, u) - xdot[I_x2] - # gnsf_val2 = A_LO @ x[I_x2] + gnsf['f_lo_fun'](x[I_x1], xdot[I_x1], z, u) - xdot[I_x2] - # - # - # gnsf_val = [gnsf_val1 gnsf_val2] - # gnsf_val = gnsf_val.simplify() - # dyn_expr_f = dyn_expr_f.simplify() - # import pdb; pdb.set_trace() - - return check diff --git a/third_party/acados/acados_template/gnsf/detect_affine_terms_reduce_nonlinearity.py b/third_party/acados/acados_template/gnsf/detect_affine_terms_reduce_nonlinearity.py deleted file mode 100644 index ebf1f373a4..0000000000 --- a/third_party/acados/acados_template/gnsf/detect_affine_terms_reduce_nonlinearity.py +++ /dev/null @@ -1,278 +0,0 @@ -# -# Copyright (c) The acados authors. -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# - -from casadi import * -from .check_reformulation import check_reformulation -from .determine_input_nonlinearity_function import determine_input_nonlinearity_function -from ..utils import casadi_length, print_casadi_expression - - -def detect_affine_terms_reduce_nonlinearity(gnsf, acados_ocp, print_info): - - ## Description - # this function takes a gnsf structure with trivial model matrices (A, B, - # E, c are zeros, and C is eye). - # It detects all affine linear terms and sets up an equivalent model in the - # GNSF structure, where all affine linear terms are modeled through the - # matrices A, B, E, c and the linear output system (LOS) is empty. - # NOTE: model is just taken as an argument to check equivalence of the - # models within the function. - - model = acados_ocp.model - if print_info: - print(" ") - print("====================================================================") - print(" ") - print("============ Detect affine-linear dependencies ==================") - print(" ") - print("====================================================================") - print(" ") - # symbolics - x = gnsf["x"] - xdot = gnsf["xdot"] - u = gnsf["u"] - z = gnsf["z"] - - # dimensions - nx = gnsf["nx"] - nu = gnsf["nu"] - nz = gnsf["nz"] - - ny_old = gnsf["ny"] - nuhat_old = gnsf["nuhat"] - - ## Represent all affine dependencies through the model matrices A, B, E, c - ## determine A - n_nodes_current = n_nodes(gnsf["phi_expr"]) - - for ii in range(casadi_length(gnsf["phi_expr"])): - fii = gnsf["phi_expr"][ii] - for ix in range(nx): - var = x[ix] - varname = var.name - # symbolic jacobian of fii w.r.t. xi - jac_fii_xi = jacobian(fii, var) - if jac_fii_xi.is_constant(): - # jacobian value - jac_fii_xi_fun = Function("jac_fii_xi_fun", [x[1]], [jac_fii_xi]) - # x[1] as input just to have a scalar input and call the function as follows: - gnsf["A"][ii, ix] = jac_fii_xi_fun(0).full() - else: - gnsf["A"][ii, ix] = 0 - if print_info: - print( - "phi(", - str(ii), - ") is nonlinear in x(", - str(ix), - ") = ", - varname, - ) - print(fii) - print("-----------------------------------------------------") - f_next = gnsf["phi_expr"] - gnsf["A"] @ x - f_next = simplify(f_next) - n_nodes_next = n_nodes(f_next) - - if print_info: - print("\n") - print(f"determined matrix A:") - print(gnsf["A"]) - print(f"reduced nonlinearity from {n_nodes_current} to {n_nodes_next} nodes") - # assert(n_nodes_current >= n_nodes_next,'n_nodes_current >= n_nodes_next FAILED') - gnsf["phi_expr"] = f_next - - check_reformulation(model, gnsf, print_info) - - ## determine B - n_nodes_current = n_nodes(gnsf["phi_expr"]) - - for ii in range(casadi_length(gnsf["phi_expr"])): - fii = gnsf["phi_expr"][ii] - for iu in range(nu): - var = u[iu] - varname = var.name - # symbolic jacobian of fii w.r.t. ui - jac_fii_ui = jacobian(fii, var) - if jac_fii_ui.is_constant(): # i.e. hessian is structural zero: - # jacobian value - jac_fii_ui_fun = Function("jac_fii_ui_fun", [x[1]], [jac_fii_ui]) - gnsf["B"][ii, iu] = jac_fii_ui_fun(0).full() - else: - gnsf["B"][ii, iu] = 0 - if print_info: - print(f"phi({ii}) is nonlinear in u(", str(iu), ") = ", varname) - print(fii) - print("-----------------------------------------------------") - f_next = gnsf["phi_expr"] - gnsf["B"] @ u - f_next = simplify(f_next) - n_nodes_next = n_nodes(f_next) - - if print_info: - print("\n") - print(f"determined matrix B:") - print(gnsf["B"]) - print(f"reduced nonlinearity from {n_nodes_current} to {n_nodes_next} nodes") - - gnsf["phi_expr"] = f_next - - check_reformulation(model, gnsf, print_info) - - ## determine E - n_nodes_current = n_nodes(gnsf["phi_expr"]) - k = vertcat(xdot, z) - - for ii in range(casadi_length(gnsf["phi_expr"])): - fii = gnsf["phi_expr"][ii] - for ik in range(casadi_length(k)): - # symbolic jacobian of fii w.r.t. ui - var = k[ik] - varname = var.name - jac_fii_ki = jacobian(fii, var) - if jac_fii_ki.is_constant(): - # jacobian value - jac_fii_ki_fun = Function("jac_fii_ki_fun", [x[1]], [jac_fii_ki]) - gnsf["E"][ii, ik] = -jac_fii_ki_fun(0).full() - else: - gnsf["E"][ii, ik] = 0 - if print_info: - print(f"phi( {ii}) is nonlinear in xdot_z({ik}) = ", varname) - print(fii) - print("-----------------------------------------------------") - f_next = gnsf["phi_expr"] + gnsf["E"] @ k - f_next = simplify(f_next) - n_nodes_next = n_nodes(f_next) - - if print_info: - print("\n") - print(f"determined matrix E:") - print(gnsf["E"]) - print(f"reduced nonlinearity from {n_nodes_current} to {n_nodes_next} nodes") - - gnsf["phi_expr"] = f_next - check_reformulation(model, gnsf, print_info) - - ## determine constant term c - - n_nodes_current = n_nodes(gnsf["phi_expr"]) - for ii in range(casadi_length(gnsf["phi_expr"])): - fii = gnsf["phi_expr"][ii] - if fii.is_constant(): - # function value goes into c - fii_fun = Function("fii_fun", [x[1]], [fii]) - gnsf["c"][ii] = fii_fun(0).full() - else: - gnsf["c"][ii] = 0 - if print_info: - print(f"phi(", str(ii), ") is NOT constant") - print(fii) - print("-----------------------------------------------------") - gnsf["phi_expr"] = gnsf["phi_expr"] - gnsf["c"] - gnsf["phi_expr"] = simplify(gnsf["phi_expr"]) - n_nodes_next = n_nodes(gnsf["phi_expr"]) - - if print_info: - print("\n") - print(f"determined vector c:") - print(gnsf["c"]) - print(f"reduced nonlinearity from {n_nodes_current} to {n_nodes_next} nodes") - - check_reformulation(model, gnsf, print_info) - - ## determine nonlinearity & corresponding matrix C - ## Reduce dimension of phi - n_nodes_current = n_nodes(gnsf["phi_expr"]) - ind_non_zero = [] - for ii in range(casadi_length(gnsf["phi_expr"])): - fii = gnsf["phi_expr"][ii] - fii = simplify(fii) - if not fii.is_zero(): - ind_non_zero = list(set.union(set(ind_non_zero), set([ii]))) - gnsf["phi_expr"] = gnsf["phi_expr"][ind_non_zero] - - # C - gnsf["C"] = np.zeros((nx + nz, len(ind_non_zero))) - for ii in range(len(ind_non_zero)): - gnsf["C"][ind_non_zero[ii], ii] = 1 - gnsf = determine_input_nonlinearity_function(gnsf) - n_nodes_next = n_nodes(gnsf["phi_expr"]) - - if print_info: - print(" ") - print("determined matrix C:") - print(gnsf["C"]) - print( - "---------------------------------------------------------------------------------" - ) - print( - "------------- Success: Affine linear terms detected -----------------------------" - ) - print( - "---------------------------------------------------------------------------------" - ) - print( - f'reduced nonlinearity dimension n_out from {nx+nz} to {gnsf["n_out"]}' - ) - print(f"reduced nonlinearity from {n_nodes_current} to {n_nodes_next} nodes") - print(" ") - print("phi now reads as:") - print_casadi_expression(gnsf["phi_expr"]) - - ## determine input of nonlinearity function - check_reformulation(model, gnsf, print_info) - - gnsf["ny"] = casadi_length(gnsf["y"]) - gnsf["nuhat"] = casadi_length(gnsf["uhat"]) - - if print_info: - print( - "-----------------------------------------------------------------------------------" - ) - print(" ") - print( - f"reduced input ny of phi from ", - str(ny_old), - " to ", - str(gnsf["ny"]), - ) - print( - f"reduced input nuhat of phi from ", - str(nuhat_old), - " to ", - str(gnsf["nuhat"]), - ) - print( - "-----------------------------------------------------------------------------------" - ) - - # if print_info: - # print(f"gnsf: {gnsf}") - - return gnsf diff --git a/third_party/acados/acados_template/gnsf/detect_gnsf_structure.py b/third_party/acados/acados_template/gnsf/detect_gnsf_structure.py deleted file mode 100644 index 24ffe643b8..0000000000 --- a/third_party/acados/acados_template/gnsf/detect_gnsf_structure.py +++ /dev/null @@ -1,240 +0,0 @@ -# -# Copyright (c) The acados authors. -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# -# Author: Jonathan Frey: jonathanpaulfrey(at)gmail.com - -from casadi import Function, jacobian, SX, vertcat, horzcat - -from .determine_trivial_gnsf_transcription import determine_trivial_gnsf_transcription -from .detect_affine_terms_reduce_nonlinearity import ( - detect_affine_terms_reduce_nonlinearity, -) -from .reformulate_with_LOS import reformulate_with_LOS -from .reformulate_with_invertible_E_mat import reformulate_with_invertible_E_mat -from .structure_detection_print_summary import structure_detection_print_summary -from .check_reformulation import check_reformulation - - -def detect_gnsf_structure(acados_ocp, transcribe_opts=None): - - ## Description - # This function takes a CasADi implicit ODE or index-1 DAE model "model" - # consisting of a CasADi expression f_impl in the symbolic CasADi - # variables x, xdot, u, z, (and possibly parameters p), which are also part - # of the model, as well as a model name. - # It will create a struct "gnsf" containing all information needed to use - # it with the gnsf integrator in acados. - # Additionally it will create the struct "reordered_model" which contains - # the permuted state vector and permuted f_impl, in which additionally some - # functions, which were made part of the linear output system of the gnsf, - # have changed signs. - - # Options: transcribe_opts is a Matlab struct consisting of booleans: - # print_info: if extensive information on how the model is processed - # is printed to the console. - # generate_gnsf_model: if the neccessary C functions to simulate the gnsf - # model with the acados implementation of the GNSF exploiting - # integrator should be generated. - # generate_gnsf_model: if the neccessary C functions to simulate the - # reordered model with the acados implementation of the IRK - # integrator should be generated. - # check_E_invertibility: if the transcription method should check if the - # assumption that the main blocks of the matrix gnsf.E are invertible - # holds. If not, the method will try to reformulate the gnsf model - # with a different model, such that the assumption holds. - - # acados_root_dir = getenv('ACADOS_INSTALL_DIR') - - ## load transcribe_opts - if transcribe_opts is None: - print("WARNING: GNSF structure detection called without transcribe_opts") - print(" using default settings") - print("") - transcribe_opts = dict() - - if "print_info" in transcribe_opts: - print_info = transcribe_opts["print_info"] - else: - print_info = 1 - print("print_info option was not set - default is true") - - if "detect_LOS" in transcribe_opts: - detect_LOS = transcribe_opts["detect_LOS"] - else: - detect_LOS = 1 - if print_info: - print("detect_LOS option was not set - default is true") - - if "check_E_invertibility" in transcribe_opts: - check_E_invertibility = transcribe_opts["check_E_invertibility"] - else: - check_E_invertibility = 1 - if print_info: - print("check_E_invertibility option was not set - default is true") - - ## Reformulate implicit index-1 DAE into GNSF form - # (Generalized nonlinear static feedback) - gnsf = determine_trivial_gnsf_transcription(acados_ocp, print_info) - gnsf = detect_affine_terms_reduce_nonlinearity(gnsf, acados_ocp, print_info) - - if detect_LOS: - gnsf = reformulate_with_LOS(acados_ocp, gnsf, print_info) - - if check_E_invertibility: - gnsf = reformulate_with_invertible_E_mat(gnsf, acados_ocp, print_info) - - # detect purely linear model - if gnsf["nx1"] == 0 and gnsf["nz1"] == 0 and gnsf["nontrivial_f_LO"] == 0: - gnsf["purely_linear"] = 1 - else: - gnsf["purely_linear"] = 0 - - structure_detection_print_summary(gnsf, acados_ocp) - check_reformulation(acados_ocp.model, gnsf, print_info) - - ## copy relevant fields from gnsf to model - acados_ocp.model.get_matrices_fun = Function() - dummy = acados_ocp.model.x[0] - model_name = acados_ocp.model.name - - get_matrices_fun = Function( - f"{model_name}_gnsf_get_matrices_fun", - [dummy], - [ - gnsf["A"], - gnsf["B"], - gnsf["C"], - gnsf["E"], - gnsf["L_x"], - gnsf["L_xdot"], - gnsf["L_z"], - gnsf["L_u"], - gnsf["A_LO"], - gnsf["c"], - gnsf["E_LO"], - gnsf["B_LO"], - gnsf["nontrivial_f_LO"], - gnsf["purely_linear"], - gnsf["ipiv_x"] + 1, - gnsf["ipiv_z"] + 1, - gnsf["c_LO"], - ], - ) - - phi = gnsf["phi_expr"] - y = gnsf["y"] - uhat = gnsf["uhat"] - p = gnsf["p"] - - jac_phi_y = jacobian(phi, y) - jac_phi_uhat = jacobian(phi, uhat) - - phi_fun = Function(f"{model_name}_gnsf_phi_fun", [y, uhat, p], [phi]) - acados_ocp.model.phi_fun = phi_fun - acados_ocp.model.phi_fun_jac_y = Function( - f"{model_name}_gnsf_phi_fun_jac_y", [y, uhat, p], [phi, jac_phi_y] - ) - acados_ocp.model.phi_jac_y_uhat = Function( - f"{model_name}_gnsf_phi_jac_y_uhat", [y, uhat, p], [jac_phi_y, jac_phi_uhat] - ) - - x1 = acados_ocp.model.x[gnsf["idx_perm_x"][: gnsf["nx1"]]] - x1dot = acados_ocp.model.xdot[gnsf["idx_perm_x"][: gnsf["nx1"]]] - if gnsf["nz1"] > 0: - z1 = acados_ocp.model.z[gnsf["idx_perm_z"][: gnsf["nz1"]]] - else: - z1 = SX.sym("z1", 0, 0) - f_lo = gnsf["f_lo_expr"] - u = acados_ocp.model.u - acados_ocp.model.f_lo_fun_jac_x1k1uz = Function( - f"{model_name}_gnsf_f_lo_fun_jac_x1k1uz", - [x1, x1dot, z1, u, p], - [ - f_lo, - horzcat( - jacobian(f_lo, x1), - jacobian(f_lo, x1dot), - jacobian(f_lo, u), - jacobian(f_lo, z1), - ), - ], - ) - - acados_ocp.model.get_matrices_fun = get_matrices_fun - - size_gnsf_A = gnsf["A"].shape - acados_ocp.dims.gnsf_nx1 = size_gnsf_A[1] - acados_ocp.dims.gnsf_nz1 = size_gnsf_A[0] - size_gnsf_A[1] - acados_ocp.dims.gnsf_nuhat = max(phi_fun.size_in(1)) - acados_ocp.dims.gnsf_ny = max(phi_fun.size_in(0)) - acados_ocp.dims.gnsf_nout = max(phi_fun.size_out(0)) - - # # dim - # model['dim_gnsf_nx1'] = gnsf['nx1'] - # model['dim_gnsf_nx2'] = gnsf['nx2'] - # model['dim_gnsf_nz1'] = gnsf['nz1'] - # model['dim_gnsf_nz2'] = gnsf['nz2'] - # model['dim_gnsf_nuhat'] = gnsf['nuhat'] - # model['dim_gnsf_ny'] = gnsf['ny'] - # model['dim_gnsf_nout'] = gnsf['n_out'] - - # # sym - # model['sym_gnsf_y'] = gnsf['y'] - # model['sym_gnsf_uhat'] = gnsf['uhat'] - - # # data - # model['dyn_gnsf_A'] = gnsf['A'] - # model['dyn_gnsf_A_LO'] = gnsf['A_LO'] - # model['dyn_gnsf_B'] = gnsf['B'] - # model['dyn_gnsf_B_LO'] = gnsf['B_LO'] - # model['dyn_gnsf_E'] = gnsf['E'] - # model['dyn_gnsf_E_LO'] = gnsf['E_LO'] - # model['dyn_gnsf_C'] = gnsf['C'] - # model['dyn_gnsf_c'] = gnsf['c'] - # model['dyn_gnsf_c_LO'] = gnsf['c_LO'] - # model['dyn_gnsf_L_x'] = gnsf['L_x'] - # model['dyn_gnsf_L_xdot'] = gnsf['L_xdot'] - # model['dyn_gnsf_L_z'] = gnsf['L_z'] - # model['dyn_gnsf_L_u'] = gnsf['L_u'] - # model['dyn_gnsf_idx_perm_x'] = gnsf['idx_perm_x'] - # model['dyn_gnsf_ipiv_x'] = gnsf['ipiv_x'] - # model['dyn_gnsf_idx_perm_z'] = gnsf['idx_perm_z'] - # model['dyn_gnsf_ipiv_z'] = gnsf['ipiv_z'] - # model['dyn_gnsf_idx_perm_f'] = gnsf['idx_perm_f'] - # model['dyn_gnsf_ipiv_f'] = gnsf['ipiv_f'] - - # # flags - # model['dyn_gnsf_nontrivial_f_LO'] = gnsf['nontrivial_f_LO'] - # model['dyn_gnsf_purely_linear'] = gnsf['purely_linear'] - - # # casadi expr - # model['dyn_gnsf_expr_phi'] = gnsf['phi_expr'] - # model['dyn_gnsf_expr_f_lo'] = gnsf['f_lo_expr'] - - return acados_ocp diff --git a/third_party/acados/acados_template/gnsf/determine_input_nonlinearity_function.py b/third_party/acados/acados_template/gnsf/determine_input_nonlinearity_function.py deleted file mode 100644 index 94aa001c79..0000000000 --- a/third_party/acados/acados_template/gnsf/determine_input_nonlinearity_function.py +++ /dev/null @@ -1,110 +0,0 @@ -# -# Copyright (c) The acados authors. -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# -# Author: Jonathan Frey: jonathanpaulfrey(at)gmail.com - -from casadi import * -from ..utils import casadi_length, is_empty - - -def determine_input_nonlinearity_function(gnsf): - - ## Description - # this function takes a structure gnsf and updates the matrices L_x, - # L_xdot, L_z, L_u and CasADi vectors y, uhat of this structure as follows: - - # given a CasADi expression phi_expr, which may depend on the variables - # (x1, x1dot, z, u), this function determines a vector y (uhat) consisting - # of all components of (x1, x1dot, z) (respectively u) that enter phi_expr. - # Additionally matrices L_x, L_xdot, L_z, L_u are determined such that - # y = L_x * x + L_xdot * xdot + L_z * z - # uhat = L_u * u - # Furthermore the dimensions ny, nuhat, n_out are updated - - ## y - y = SX.sym('y', 0, 0) - # components of x1 - for ii in range(gnsf["nx1"]): - if which_depends(gnsf["phi_expr"], gnsf["x"][ii])[0]: - y = vertcat(y, gnsf["x"][ii]) - # else: - # x[ii] is not part of y - # components of x1dot - for ii in range(gnsf["nx1"]): - if which_depends(gnsf["phi_expr"], gnsf["xdot"][ii])[0]: - print(gnsf["phi_expr"], "depends on", gnsf["xdot"][ii]) - y = vertcat(y, gnsf["xdot"][ii]) - # else: - # xdot[ii] is not part of y - # components of z - for ii in range(gnsf["nz1"]): - if which_depends(gnsf["phi_expr"], gnsf["z"][ii])[0]: - y = vertcat(y, gnsf["z"][ii]) - # else: - # z[ii] is not part of y - ## uhat - uhat = SX.sym('uhat', 0, 0) - # components of u - for ii in range(gnsf["nu"]): - if which_depends(gnsf["phi_expr"], gnsf["u"][ii])[0]: - uhat = vertcat(uhat, gnsf["u"][ii]) - # else: - # u[ii] is not part of uhat - ## generate gnsf['phi_expr_fun'] - # linear input matrices - if is_empty(y): - gnsf["L_x"] = [] - gnsf["L_xdot"] = [] - gnsf["L_u"] = [] - gnsf["L_z"] = [] - else: - dummy = SX.sym("dummy_input", 0) - L_x_fun = Function( - "L_x_fun", [dummy], [jacobian(y, gnsf["x"][range(gnsf["nx1"])])] - ) - L_xdot_fun = Function( - "L_xdot_fun", [dummy], [jacobian(y, gnsf["xdot"][range(gnsf["nx1"])])] - ) - L_z_fun = Function( - "L_z_fun", [dummy], [jacobian(y, gnsf["z"][range(gnsf["nz1"])])] - ) - L_u_fun = Function("L_u_fun", [dummy], [jacobian(uhat, gnsf["u"])]) - - gnsf["L_x"] = L_x_fun(0).full() - gnsf["L_xdot"] = L_xdot_fun(0).full() - gnsf["L_u"] = L_u_fun(0).full() - gnsf["L_z"] = L_z_fun(0).full() - gnsf["y"] = y - gnsf["uhat"] = uhat - - gnsf["ny"] = casadi_length(y) - gnsf["nuhat"] = casadi_length(uhat) - gnsf["n_out"] = casadi_length(gnsf["phi_expr"]) - - return gnsf diff --git a/third_party/acados/acados_template/gnsf/determine_trivial_gnsf_transcription.py b/third_party/acados/acados_template/gnsf/determine_trivial_gnsf_transcription.py deleted file mode 100644 index 23c2440537..0000000000 --- a/third_party/acados/acados_template/gnsf/determine_trivial_gnsf_transcription.py +++ /dev/null @@ -1,155 +0,0 @@ -# -# Copyright (c) The acados authors. -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# - -from casadi import * -import numpy as np -from ..utils import casadi_length, idx_perm_to_ipiv -from .determine_input_nonlinearity_function import determine_input_nonlinearity_function -from .check_reformulation import check_reformulation - - -def determine_trivial_gnsf_transcription(acados_ocp, print_info): - ## Description - # this function takes a model of an implicit ODE/ index-1 DAE and sets up - # an equivalent model in the GNSF structure, with empty linear output - # system and trivial model matrices, i.e. A, B, E, c are zeros, and C is - # eye. - no structure is exploited - - model = acados_ocp.model - # initial print - print("*****************************************************************") - print(" ") - print(f"****** Restructuring {model.name} model ***********") - print(" ") - print("*****************************************************************") - - # load model - f_impl_expr = model.f_impl_expr - - model_name_prefix = model.name - - # x - x = model.x - nx = acados_ocp.dims.nx - # check type - if isinstance(x[0], SX): - isSX = True - else: - print("GNSF detection only works for SX CasADi type!!!") - import pdb - - pdb.set_trace() - # xdot - xdot = model.xdot - # u - nu = acados_ocp.dims.nu - if nu == 0: - u = SX.sym("u", 0, 0) - else: - u = model.u - - nz = acados_ocp.dims.nz - if nz == 0: - z = SX.sym("z", 0, 0) - else: - z = model.z - - p = model.p - nparam = acados_ocp.dims.np - - # avoid SX of size 0x1 - if casadi_length(u) == 0: - u = SX.sym("u", 0, 0) - nu = 0 - ## initialize gnsf struct - # dimensions - gnsf = {"nx": nx, "nu": nu, "nz": nz, "np": nparam} - gnsf["nx1"] = nx - gnsf["nx2"] = 0 - gnsf["nz1"] = nz - gnsf["nz2"] = 0 - gnsf["nuhat"] = nu - gnsf["ny"] = 2 * nx + nz - - gnsf["phi_expr"] = f_impl_expr - gnsf["A"] = np.zeros((nx + nz, nx)) - gnsf["B"] = np.zeros((nx + nz, nu)) - gnsf["E"] = np.zeros((nx + nz, nx + nz)) - gnsf["c"] = np.zeros((nx + nz, 1)) - gnsf["C"] = np.eye(nx + nz) - gnsf["name"] = model_name_prefix - - gnsf["x"] = x - gnsf["xdot"] = xdot - gnsf["z"] = z - gnsf["u"] = u - gnsf["p"] = p - - gnsf = determine_input_nonlinearity_function(gnsf) - - gnsf["A_LO"] = [] - gnsf["E_LO"] = [] - gnsf["B_LO"] = [] - gnsf["c_LO"] = [] - gnsf["f_lo_expr"] = [] - - # permutation - gnsf["idx_perm_x"] = range(nx) # matlab-style) - gnsf["ipiv_x"] = idx_perm_to_ipiv(gnsf["idx_perm_x"]) # blasfeo-style - gnsf["idx_perm_z"] = range(nz) - gnsf["ipiv_z"] = idx_perm_to_ipiv(gnsf["idx_perm_z"]) - gnsf["idx_perm_f"] = range((nx + nz)) - gnsf["ipiv_f"] = idx_perm_to_ipiv(gnsf["idx_perm_f"]) - - gnsf["nontrivial_f_LO"] = 0 - - check_reformulation(model, gnsf, print_info) - if print_info: - print(f"Success: Set up equivalent GNSF model with trivial matrices") - print(" ") - if print_info: - print( - "-----------------------------------------------------------------------------------" - ) - print(" ") - print( - "reduced input ny of phi from ", - str(2 * nx + nz), - " to ", - str(gnsf["ny"]), - ) - print( - "reduced input nuhat of phi from ", str(nu), " to ", str(gnsf["nuhat"]) - ) - print(" ") - print( - "-----------------------------------------------------------------------------------" - ) - return gnsf diff --git a/third_party/acados/acados_template/gnsf/matlab to python.md b/third_party/acados/acados_template/gnsf/matlab to python.md deleted file mode 100644 index 53a0ed971e..0000000000 --- a/third_party/acados/acados_template/gnsf/matlab to python.md +++ /dev/null @@ -1,43 +0,0 @@ -# matlab to python - -% -> # - -; -> - -from casadi import * --> -from casadi import * - - -print\('(.*)'\) -print('$1') - -print\(\['(.*)'\]\) -print(f'$1') - -keyboard -import pdb; pdb.set_trace() - - -range((([^))]*)) -range($1) - -\s*end --> -nothing - - -if (.*) -if $1: - -else -else: - -num2str -str - -for ([a-z_]*) = -for $1 in - -length\( -len( \ No newline at end of file diff --git a/third_party/acados/acados_template/gnsf/reformulate_with_LOS.py b/third_party/acados/acados_template/gnsf/reformulate_with_LOS.py deleted file mode 100644 index 297a56556c..0000000000 --- a/third_party/acados/acados_template/gnsf/reformulate_with_LOS.py +++ /dev/null @@ -1,394 +0,0 @@ -# -# Copyright (c) The acados authors. -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# -# Author: Jonathan Frey: jonathanpaulfrey(at)gmail.com - -from .determine_input_nonlinearity_function import determine_input_nonlinearity_function -from .check_reformulation import check_reformulation -from casadi import * -from ..utils import casadi_length, idx_perm_to_ipiv, is_empty - - -def reformulate_with_LOS(acados_ocp, gnsf, print_info): - - ## Description: - # This function takes an intitial transcription of the implicit ODE model - # "model" into "gnsf" and reformulates "gnsf" with a linear output system - # (LOS), containing as many states of the model as possible. - # Therefore it might be that the state vector and the implicit function - # vector have to be reordered. This reordered model is part of the output, - # namely reordered_model. - - ## import CasADi and load models - model = acados_ocp.model - - # symbolics - x = gnsf["x"] - xdot = gnsf["xdot"] - u = gnsf["u"] - z = gnsf["z"] - - # dimensions - nx = gnsf["nx"] - nz = gnsf["nz"] - - # get model matrices - A = gnsf["A"] - B = gnsf["B"] - C = gnsf["C"] - E = gnsf["E"] - c = gnsf["c"] - - A_LO = gnsf["A_LO"] - - y = gnsf["y"] - - phi_old = gnsf["phi_expr"] - - if print_info: - print(" ") - print("=================================================================") - print(" ") - print("================ Detect Linear Output System ===============") - print(" ") - print("=================================================================") - print(" ") - ## build initial I_x1 and I_x2_candidates - # I_xrange( all components of x for which either xii or xdot_ii enters y): - # I_LOS_candidates: the remaining components - - I_nsf_components = set() - I_LOS_candidates = set() - - if gnsf["ny"] > 0: - for ii in range(nx): - if which_depends(y, x[ii])[0] or which_depends(y, xdot[ii])[0]: - # i.e. xii or xiidot are part of y, and enter phi_expr - if print_info: - print(f"x_{ii} is part of x1") - I_nsf_components = set.union(I_nsf_components, set([ii])) - else: - # i.e. neither xii nor xiidot are part of y, i.e. enter phi_expr - I_LOS_candidates = set.union(I_LOS_candidates, set([ii])) - if print_info: - print(" ") - for ii in range(nz): - if which_depends(y, z[ii])[0]: - # i.e. xii or xiidot are part of y, and enter phi_expr - if print_info: - print(f"z_{ii} is part of x1") - I_nsf_components = set.union(I_nsf_components, set([ii + nx])) - else: - # i.e. neither xii nor xiidot are part of y, i.e. enter phi_expr - I_LOS_candidates = set.union(I_LOS_candidates, set([ii + nx])) - else: - I_LOS_candidates = set(range((nx + nz))) - if print_info: - print(" ") - print(f"I_LOS_candidates {I_LOS_candidates}") - new_nsf_components = I_nsf_components - I_nsf_eq = set([]) - unsorted_dyn = set(range(nx + nz)) - xdot_z = vertcat(xdot, z) - - ## determine components of Linear Output System - # determine maximal index set I_x2 - # such that the components x(I_x2) can be written as a LOS - Eq_map = [] - while True: - ## find equations corresponding to new_nsf_components - for ii in new_nsf_components: - current_var = xdot_z[ii] - var_name = current_var.name - - # print( unsorted_dyn) - # print("np.nonzero(E[:,ii])[0]",np.nonzero(E[:,ii])[0]) - I_eq = set.intersection(set(np.nonzero(E[:, ii])[0]), unsorted_dyn) - if len(I_eq) == 1: - i_eq = I_eq.pop() - if print_info: - print(f"component {i_eq} is associated with state {ii}") - elif len(I_eq) > 1: # x_ii_dot occurs in more than 1 eq linearly - # find the equation with least linear dependencies on - # I_LOS_cancidates - number_of_eq = 0 - candidate_dependencies = np.zeros(len(I_eq), 1) - I_x2_candidates = set.intersection(I_LOS_candidates, set(range(nx))) - for eq in I_eq: - depending_candidates = set.union( - np.nonzero(E[eq, I_LOS_candidates])[0], - np.nonzero(A[eq, I_x2_candidates])[0], - ) - candidate_dependencies[number_of_eq] = +len(depending_candidates) - number_of_eq += 1 - number_of_eq = np.argmin(candidate_dependencies) - i_eq = I_eq[number_of_eq] - else: ## x_ii_dot does not occur linearly in any of the unsorted dynamics - for j in unsorted_dyn: - phi_eq_j = gnsf["phi_expr"][np.nonzero(C[j, :])[0]] - if which_depends(phi_eq_j, xdot_z(ii))[0]: - I_eq = set.union(I_eq, j) - if is_empty(I_eq): - I_eq = unsorted_dyn - # find the equation with least linear dependencies on I_LOS_cancidates - number_of_eq = 0 - candidate_dependencies = np.zeros(len(I_eq), 1) - I_x2_candidates = set.intersection(I_LOS_candidates, set(range(nx))) - for eq in I_eq: - depending_candidates = set.union( - np.nonzero(E[eq, I_LOS_candidates])[0], - np.nonzero(A[eq, I_x2_candidates])[0], - ) - candidate_dependencies[number_of_eq] = +len(depending_candidates) - number_of_eq += 1 - number_of_eq = np.argmin(candidate_dependencies) - i_eq = I_eq[number_of_eq] - ## add 1 * [xdot,z](ii) to both sides of i_eq - if print_info: - print( - "adding 1 * ", - var_name, - " to both sides of equation ", - i_eq, - ".", - ) - gnsf["E"][i_eq, ii] = 1 - i_phi = np.nonzero(gnsf["C"][i_eq, :]) - if is_empty(i_phi): - i_phi = len(gnsf["phi_expr"]) + 1 - gnsf["C"][i_eq, i_phi] = 1 # add column to C with 1 entry - gnsf["phi_expr"] = vertcat(gnsf["phi_expr"], 0) - gnsf["phi_expr"][i_phi] = ( - gnsf["phi_expr"](i_phi) - + gnsf["E"][i_eq, ii] / gnsf["C"][i_eq, i_phi] * xdot_z[ii] - ) - if print_info: - print( - "detected equation ", - i_eq, - " to correspond to variable ", - var_name, - ) - I_nsf_eq = set.union(I_nsf_eq, {i_eq}) - # remove i_eq from unsorted_dyn - unsorted_dyn.remove(i_eq) - Eq_map.append([ii, i_eq]) - - ## add components to I_x1 - for eq in I_nsf_eq: - I_linear_dependence = set.union( - set(np.nonzero(A[eq, :])[0]), set(np.nonzero(E[eq, :])[0]) - ) - I_nsf_components = set.union(I_linear_dependence, I_nsf_components) - # I_nsf_components = I_nsf_components[:] - - new_nsf_components = set.intersection(I_LOS_candidates, I_nsf_components) - if is_empty(new_nsf_components): - if print_info: - print("new_nsf_components is empty") - break - # remove new_nsf_components from candidates - I_LOS_candidates = set.difference(I_LOS_candidates, new_nsf_components) - if not is_empty(Eq_map): - # [~, new_eq_order] = sort(Eq_map(1,:)) - # I_nsf_eq = Eq_map(2, new_eq_order ) - for count, m in enumerate(Eq_map): - m.append(count) - sorted(Eq_map, key=lambda x: x[1]) - new_eq_order = [m[2] for m in Eq_map] - Eq_map = [Eq_map[i] for i in new_eq_order] - I_nsf_eq = [m[1] for m in Eq_map] - - else: - I_nsf_eq = [] - - I_LOS_components = I_LOS_candidates - I_LOS_eq = sorted(set.difference(set(range(nx + nz)), I_nsf_eq)) - I_nsf_eq = sorted(I_nsf_eq) - - I_x1 = set.intersection(I_nsf_components, set(range(nx))) - I_z1 = set.intersection(I_nsf_components, set(range(nx, nx + nz))) - I_z1 = set([i - nx for i in I_z1]) - - I_x2 = set.intersection(I_LOS_components, set(range(nx))) - I_z2 = set.intersection(I_LOS_components, set(range(nx, nx + nz))) - I_z2 = set([i - nx for i in I_z2]) - - if print_info: - print(f"I_x1 {I_x1}, I_x2 {I_x2}") - - ## permute x, xdot - if is_empty(I_x1): - x1 = [] - x1dot = [] - else: - x1 = x[list(I_x1)] - x1dot = xdot[list(I_x1)] - if is_empty(I_x2): - x2 = [] - x2dot = [] - else: - x2 = x[list(I_x2)] - x2dot = xdot[list(I_x2)] - if is_empty(I_z1): - z1 = [] - else: - z1 = z(I_z1) - if is_empty(I_z2): - z2 = [] - else: - z2 = z[list(I_z2)] - - I_x1 = sorted(I_x1) - I_x2 = sorted(I_x2) - I_z1 = sorted(I_z1) - I_z2 = sorted(I_z2) - gnsf["xdot"] = vertcat(x1dot, x2dot) - gnsf["x"] = vertcat(x1, x2) - gnsf["z"] = vertcat(z1, z2) - gnsf["nx1"] = len(I_x1) - gnsf["nx2"] = len(I_x2) - gnsf["nz1"] = len(I_z1) - gnsf["nz2"] = len(I_z2) - - # store permutations - gnsf["idx_perm_x"] = I_x1 + I_x2 - gnsf["ipiv_x"] = idx_perm_to_ipiv(gnsf["idx_perm_x"]) - gnsf["idx_perm_z"] = I_z1 + I_z2 - gnsf["ipiv_z"] = idx_perm_to_ipiv(gnsf["idx_perm_z"]) - gnsf["idx_perm_f"] = I_nsf_eq + I_LOS_eq - gnsf["ipiv_f"] = idx_perm_to_ipiv(gnsf["idx_perm_f"]) - - f_LO = SX.sym("f_LO", 0, 0) - - ## rewrite I_LOS_eq as LOS - if gnsf["n_out"] == 0: - C_phi = np.zeros(gnsf["nx"] + gnsf["nz"], 1) - else: - C_phi = C @ phi_old - if gnsf["nx1"] == 0: - Ax1 = np.zeros(gnsf["nx"] + gnsf["nz"], 1) - else: - Ax1 = A[:, sorted(I_x1)] @ x1 - if gnsf["nx1"] + gnsf["nz1"] == 0: - lhs_nsf = np.zeros(gnsf["nx"] + gnsf["nz"], 1) - else: - lhs_nsf = E[:, sorted(I_nsf_components)] @ vertcat(x1, z1) - n_LO = len(I_LOS_eq) - B_LO = np.zeros((n_LO, gnsf["nu"])) - A_LO = np.zeros((gnsf["nx2"] + gnsf["nz2"], gnsf["nx2"])) - E_LO = np.zeros((n_LO, n_LO)) - c_LO = np.zeros((n_LO, 1)) - - I_LOS_eq = list(I_LOS_eq) - for eq in I_LOS_eq: - i_LO = I_LOS_eq.index(eq) - f_LO = vertcat(f_LO, Ax1[eq] + C_phi[eq] - lhs_nsf[eq]) - print(f"eq {eq} I_LOS_components {I_LOS_components}, i_LO {i_LO}, f_LO {f_LO}") - E_LO[i_LO, :] = E[eq, sorted(I_LOS_components)] - A_LO[i_LO, :] = A[eq, I_x2] - c_LO[i_LO, :] = c[eq] - B_LO[i_LO, :] = B[eq, :] - if casadi_length(f_LO) == 0: - f_LO = SX.zeros((gnsf["nx2"] + gnsf["nz2"], 1)) - f_LO = simplify(f_LO) - gnsf["A_LO"] = A_LO - gnsf["E_LO"] = E_LO - gnsf["B_LO"] = B_LO - gnsf["c_LO"] = c_LO - gnsf["f_lo_expr"] = f_LO - - ## remove I_LOS_eq from NSF type system - gnsf["A"] = gnsf["A"][np.ix_(sorted(I_nsf_eq), sorted(I_x1))] - gnsf["B"] = gnsf["B"][sorted(I_nsf_eq), :] - gnsf["C"] = gnsf["C"][sorted(I_nsf_eq), :] - gnsf["E"] = gnsf["E"][np.ix_(sorted(I_nsf_eq), sorted(I_nsf_components))] - gnsf["c"] = gnsf["c"][sorted(I_nsf_eq), :] - - ## reduce phi, C - I_nonzero = [] - for ii in range(gnsf["C"].shape[1]): # n_colums of C: - print(f"ii {ii}") - if not all(gnsf["C"][:, ii] == 0): # if column ~= 0 - I_nonzero.append(ii) - gnsf["C"] = gnsf["C"][:, I_nonzero] - gnsf["phi_expr"] = gnsf["phi_expr"][I_nonzero] - - gnsf = determine_input_nonlinearity_function(gnsf) - - check_reformulation(model, gnsf, print_info) - - gnsf["nontrivial_f_LO"] = 0 - if not is_empty(gnsf["f_lo_expr"]): - for ii in range(casadi_length(gnsf["f_lo_expr"])): - fii = gnsf["f_lo_expr"][ii] - if not fii.is_zero(): - gnsf["nontrivial_f_LO"] = 1 - if not gnsf["nontrivial_f_LO"] and print_info: - print("f_LO is fully trivial (== 0)") - check_reformulation(model, gnsf, print_info) - - if print_info: - print("") - print( - "---------------------------------------------------------------------------------" - ) - print( - "------------- Success: Linear Output System (LOS) detected ----------------------" - ) - print( - "---------------------------------------------------------------------------------" - ) - print("") - print( - "==>> moved ", - gnsf["nx2"], - "differential states and ", - gnsf["nz2"], - " algebraic variables to the Linear Output System", - ) - print( - "==>> recuced output dimension of phi from ", - casadi_length(phi_old), - " to ", - casadi_length(gnsf["phi_expr"]), - ) - print(" ") - print("Matrices defining the LOS read as") - print(" ") - print("E_LO =") - print(gnsf["E_LO"]) - print("A_LO =") - print(gnsf["A_LO"]) - print("B_LO =") - print(gnsf["B_LO"]) - print("c_LO =") - print(gnsf["c_LO"]) - - return gnsf diff --git a/third_party/acados/acados_template/gnsf/reformulate_with_invertible_E_mat.py b/third_party/acados/acados_template/gnsf/reformulate_with_invertible_E_mat.py deleted file mode 100644 index 21ab8ebfd5..0000000000 --- a/third_party/acados/acados_template/gnsf/reformulate_with_invertible_E_mat.py +++ /dev/null @@ -1,167 +0,0 @@ -# -# Copyright (c) The acados authors. -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# -# Author: Jonathan Frey: jonathanpaulfrey(at)gmail.com - -from casadi import * -from .determine_input_nonlinearity_function import determine_input_nonlinearity_function -from .check_reformulation import check_reformulation - - -def reformulate_with_invertible_E_mat(gnsf, model, print_info): - ## Description - # this function checks that the necessary condition to apply the gnsf - # structure exploiting integrator to a model, namely that the matrices E11, - # E22 are invertible holds. - # if this is not the case, it will make these matrices invertible and add: - # corresponding terms, to the term C * phi, such that the obtained model is - # still equivalent - - # check invertibility of E11, E22 and reformulate if needed: - ind_11 = range(gnsf["nx1"]) - ind_22 = range(gnsf["nx1"], gnsf["nx1"] + gnsf["nz1"]) - - if print_info: - print(" ") - print("----------------------------------------------------") - print("checking rank of E11 and E22") - print("----------------------------------------------------") - ## check if E11, E22 are invertible: - z_check = False - if gnsf["nz1"] > 0: - z_check = ( - np.linalg.matrix_rank(gnsf["E"][np.ix_(ind_22, ind_22)]) != gnsf["nz1"] - ) - - if ( - np.linalg.matrix_rank(gnsf["E"][np.ix_(ind_11, ind_11)]) != gnsf["nx1"] - or z_check - ): - # print warning (always) - print(f"the rank of E11 or E22 is not full after the reformulation") - print("") - print( - f"the script will try to reformulate the model with an invertible matrix instead" - ) - print( - f"NOTE: this feature is based on a heuristic, it should be used with care!!!" - ) - - ## load models - xdot = gnsf["xdot"] - z = gnsf["z"] - - # # GNSF - # get dimensions - nx1 = gnsf["nx1"] - x1dot = xdot[range(nx1)] - - k = vertcat(x1dot, z) - for i in [1, 2]: - if i == 1: - ind = range(gnsf["nx1"]) - else: - ind = range(gnsf["nx1"], gnsf["nx1"] + gnsf["nz1"]) - mat = gnsf["E"][np.ix_(ind, ind)] - import pdb - - pdb.set_trace() - while np.linalg.matrix_rank(mat) < len(ind): - # import pdb; pdb.set_trace() - if print_info: - print(" ") - print(f"the rank of E", str(i), str(i), " is not full") - print( - f"the algorithm will try to reformulate the model with an invertible matrix instead" - ) - print( - f"NOTE: this feature is not super stable and might need more testing!!!!!!" - ) - for sub_max in ind: - sub_ind = range(min(ind), sub_max) - # regard the submatrix mat(sub_ind, sub_ind) - sub_mat = gnsf["E"][sub_ind, sub_ind] - if np.linalg.matrix_rank(sub_mat) < len(sub_ind): - # reformulate the model by adding a 1 to last diagonal - # element and changing rhs respectively. - gnsf["E"][sub_max, sub_max] = gnsf["E"][sub_max, sub_max] + 1 - # this means adding the term 1 * k(sub_max) to the sub_max - # row of the l.h.s - if len(np.nonzero(gnsf["C"][sub_max, :])[0]) == 0: - # if isempty(find(gnsf['C'](sub_max,:), 1)): - # add new nonlinearity entry - gnsf["C"][sub_max, gnsf["n_out"] + 1] = 1 - gnsf["phi_expr"] = vertcat(gnsf["phi_expr"], k[sub_max]) - else: - ind_f = np.nonzero(gnsf["C"][sub_max, :])[0] - if len(ind_f) != 1: - raise Exception("C is assumed to be a selection matrix") - else: - ind_f = ind_f[0] - # add term to corresponding nonlinearity entry - # note: herbey we assume that C is a selection matrix, - # i.e. gnsf['phi_expr'](ind_f) is only entering one equation - - gnsf["phi_expr"][ind_f] = ( - gnsf["phi_expr"][ind_f] - + k[sub_max] / gnsf["C"][sub_max, ind_f] - ) - gnsf = determine_input_nonlinearity_function(gnsf) - check_reformulation(model, gnsf, print_info) - print("successfully reformulated the model with invertible matrices E11, E22") - else: - if print_info: - print(" ") - print( - "the rank of both E11 and E22 is naturally full after the reformulation " - ) - print("==> model reformulation finished") - print(" ") - if (gnsf['nx2'] > 0 or gnsf['nz2'] > 0) and det(gnsf["E_LO"]) == 0: - print( - "_______________________________________________________________________________________________________" - ) - print(" ") - print("TAKE CARE ") - print("E_LO matrix is NOT regular after automatic transcription!") - print("->> this means the model CANNOT be used with the gnsf integrator") - print( - "->> it probably means that one entry (of xdot or z) that was moved to the linear output type system" - ) - print(" does not appear in the model at all (zero column in E_LO)") - print(" OR: the columns of E_LO are linearly dependent ") - print(" ") - print( - " SOLUTIONs: a) go through your model & check equations the method wanted to move to LOS" - ) - print(" b) deactivate the detect_LOS option") - print( - "_______________________________________________________________________________________________________" - ) - return gnsf diff --git a/third_party/acados/acados_template/gnsf/structure_detection_print_summary.py b/third_party/acados/acados_template/gnsf/structure_detection_print_summary.py deleted file mode 100644 index db2d18758e..0000000000 --- a/third_party/acados/acados_template/gnsf/structure_detection_print_summary.py +++ /dev/null @@ -1,174 +0,0 @@ -# -# Copyright (c) The acados authors. -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# -# Author: Jonathan Frey: jonathanpaulfrey(at)gmail.com - -from casadi import n_nodes -import numpy as np - - -def structure_detection_print_summary(gnsf, acados_ocp): - - ## Description - # this function prints the most important info after determining a GNSF - # reformulation of the implicit model "initial_model" into "gnsf", which is - # equivalent to the "reordered_model". - model = acados_ocp.model - # # GNSF - # get dimensions - nx = gnsf["nx"] - nu = gnsf["nu"] - nz = gnsf["nz"] - - nx1 = gnsf["nx1"] - nx2 = gnsf["nx2"] - - nz1 = gnsf["nz1"] - nz2 = gnsf["nz2"] - - # np = gnsf['np'] - n_out = gnsf["n_out"] - ny = gnsf["ny"] - nuhat = gnsf["nuhat"] - - # - f_impl_expr = model.f_impl_expr - n_nodes_initial = n_nodes(model.f_impl_expr) - # x_old = model.x - # f_impl_old = model.f_impl_expr - - x = gnsf["x"] - z = gnsf["z"] - - phi_current = gnsf["phi_expr"] - - ## PRINT SUMMARY -- STRUCHTRE DETECTION - print(" ") - print( - "*********************************************************************************************" - ) - print(" ") - print( - "****************** SUCCESS: GNSF STRUCTURE DETECTION COMPLETE !!! ***************" - ) - print(" ") - print( - "*********************************************************************************************" - ) - print(" ") - print( - f"========================= STRUCTURE DETECTION SUMMARY ====================================" - ) - print(" ") - print("-------- Nonlinear Static Feedback type system --------") - print(" ") - print(" successfully transcribed dynamic system model into GNSF structure ") - print(" ") - print( - "reduced dimension of nonlinearity phi from ", - str(nx + nz), - " to ", - str(gnsf["n_out"]), - ) - print(" ") - print( - "reduced input dimension of nonlinearity phi from ", - 2 * nx + nz + nu, - " to ", - gnsf["ny"] + gnsf["nuhat"], - ) - print(" ") - print(f"reduced number of nodes in CasADi expression of nonlinearity phi from {n_nodes_initial} to {n_nodes(phi_current)}\n") - print("----------- Linear Output System (LOS) ---------------") - if nx2 + nz2 > 0: - print(" ") - print(f"introduced Linear Output System of size ", str(nx2 + nz2)) - print(" ") - if nx2 > 0: - print("consisting of the states:") - print(" ") - print(x[range(nx1, nx)]) - print(" ") - if nz2 > 0: - print("and algebraic variables:") - print(" ") - print(z[range(nz1, nz)]) - print(" ") - if gnsf["purely_linear"] == 1: - print(" ") - print("Model is fully linear!") - print(" ") - if not all(gnsf["idx_perm_x"] == np.array(range(nx))): - print(" ") - print( - "--------------------------------------------------------------------------------------------------" - ) - print( - "NOTE: permuted differential state vector x, such that x_gnsf = x(idx_perm_x) with idx_perm_x =" - ) - print(" ") - print(gnsf["idx_perm_x"]) - if nz != 0 and not all(gnsf["idx_perm_z"] == np.array(range(nz))): - print(" ") - print( - "--------------------------------------------------------------------------------------------------" - ) - print( - "NOTE: permuted algebraic state vector z, such that z_gnsf = z(idx_perm_z) with idx_perm_z =" - ) - print(" ") - print(gnsf["idx_perm_z"]) - if not all(gnsf["idx_perm_f"] == np.array(range(nx + nz))): - print(" ") - print( - "--------------------------------------------------------------------------------------------------" - ) - print( - "NOTE: permuted rhs expression vector f, such that f_gnsf = f(idx_perm_f) with idx_perm_f =" - ) - print(" ") - print(gnsf["idx_perm_f"]) - ## print GNSF dimensions - print( - "--------------------------------------------------------------------------------------------------------" - ) - print(" ") - print("The dimensions of the GNSF reformulated model read as:") - print(" ") - # T_dim = table(nx, nu, nz, np, nx1, nz1, n_out, ny, nuhat) - # print( T_dim ) - print(f"nx ", {nx}) - print(f"nu ", {nu}) - print(f"nz ", {nz}) - # print(f"np ", {np}) - print(f"nx1 ", {nx1}) - print(f"nz1 ", {nz1}) - print(f"n_out ", {n_out}) - print(f"ny ", {ny}) - print(f"nuhat ", {nuhat}) diff --git a/third_party/acados/acados_template/simulink_default_opts.json b/third_party/acados/acados_template/simulink_default_opts.json deleted file mode 100644 index 5d178fef85..0000000000 --- a/third_party/acados/acados_template/simulink_default_opts.json +++ /dev/null @@ -1,44 +0,0 @@ -{ - "outputs": { - "u0": 1, - "utraj": 0, - "xtraj": 0, - "solver_status": 1, - "cost_value": 0, - "KKT_residual": 1, - "KKT_residuals": 0, - "x1": 1, - "CPU_time": 1, - "CPU_time_sim": 0, - "CPU_time_qp": 0, - "CPU_time_lin": 0, - "sqp_iter": 1 - }, - "inputs": { - "lbx_0": 1, - "ubx_0": 1, - "parameter_traj": 1, - "y_ref_0": 1, - "y_ref": 1, - "y_ref_e": 1, - "lbx": 1, - "ubx": 1, - "lbx_e": 1, - "ubx_e": 1, - "lbu": 1, - "ubu": 1, - "lg": 1, - "ug": 1, - "lh": 1, - "uh": 1, - "lh_e": 1, - "uh_e": 1, - "cost_W_0": 0, - "cost_W": 0, - "cost_W_e": 0, - "reset_solver": 0, - "x_init": 0, - "u_init": 0 - }, - "samplingtime": "t0" -} diff --git a/third_party/acados/acados_template/utils.py b/third_party/acados/acados_template/utils.py deleted file mode 100644 index f27617fa30..0000000000 --- a/third_party/acados/acados_template/utils.py +++ /dev/null @@ -1,434 +0,0 @@ -# -# Copyright (c) The acados authors. -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# - -import os, sys, json -import urllib.request -import shutil -import numpy as np -from casadi import SX, MX, DM, Function, CasadiMeta - -ALLOWED_CASADI_VERSIONS = ('3.5.6', '3.5.5', '3.5.4', '3.5.3', '3.5.2', '3.5.1', '3.4.5', '3.4.0') - -TERA_VERSION = "0.0.34" - -PLATFORM2TERA = { - "linux": "linux", - "darwin": "osx", - "win32": "windows" -} - - -def get_acados_path(): - ACADOS_PATH = os.environ.get('ACADOS_SOURCE_DIR') - if not ACADOS_PATH: - acados_template_path = os.path.dirname(os.path.abspath(__file__)) - acados_path = os.path.join(acados_template_path, '..','..','..') - ACADOS_PATH = os.path.realpath(acados_path) - msg = 'Warning: Did not find environment variable ACADOS_SOURCE_DIR, ' - msg += 'guessed ACADOS_PATH to be {}.\n'.format(ACADOS_PATH) - msg += 'Please export ACADOS_SOURCE_DIR to avoid this warning.' - print(msg) - return ACADOS_PATH - - -def get_python_interface_path(): - ACADOS_PYTHON_INTERFACE_PATH = os.environ.get('ACADOS_PYTHON_INTERFACE_PATH') - if not ACADOS_PYTHON_INTERFACE_PATH: - acados_path = get_acados_path() - ACADOS_PYTHON_INTERFACE_PATH = os.path.join(acados_path, 'interfaces', 'acados_template', 'acados_template') - return ACADOS_PYTHON_INTERFACE_PATH - - -def get_tera_exec_path(): - TERA_PATH = os.environ.get('TERA_PATH') - if not TERA_PATH: - TERA_PATH = os.path.join(get_acados_path(), 'bin', 't_renderer') - if os.name == 'nt': - TERA_PATH += '.exe' - return TERA_PATH - - -def check_casadi_version(): - casadi_version = CasadiMeta.version() - if casadi_version in ALLOWED_CASADI_VERSIONS: - return - else: - msg = 'Warning: Please note that the following versions of CasADi are ' - msg += 'officially supported: {}.\n '.format(" or ".join(ALLOWED_CASADI_VERSIONS)) - msg += 'If there is an incompatibility with the CasADi generated code, ' - msg += 'please consider changing your CasADi version.\n' - msg += 'Version {} currently in use.'.format(casadi_version) - print(msg) - - -def is_column(x): - if isinstance(x, np.ndarray): - if x.ndim == 1: - return True - elif x.ndim == 2 and x.shape[1] == 1: - return True - else: - return False - elif isinstance(x, (MX, SX, DM)): - if x.shape[1] == 1: - return True - elif x.shape[0] == 0 and x.shape[1] == 0: - return True - else: - return False - elif x == None or x == []: - return False - else: - raise Exception("is_column expects one of the following types: np.ndarray, casadi.MX, casadi.SX." - + " Got: " + str(type(x))) - - -def is_empty(x): - if isinstance(x, (MX, SX, DM)): - return x.is_empty() - elif isinstance(x, np.ndarray): - if np.prod(x.shape) == 0: - return True - else: - return False - elif x == None: - return True - elif isinstance(x, (set, list)): - if len(x)==0: - return True - else: - return False - else: - raise Exception("is_empty expects one of the following types: casadi.MX, casadi.SX, " - + "None, numpy array empty list, set. Got: " + str(type(x))) - - -def casadi_length(x): - if isinstance(x, (MX, SX, DM)): - return int(np.prod(x.shape)) - else: - raise Exception("casadi_length expects one of the following types: casadi.MX, casadi.SX." - + " Got: " + str(type(x))) - - -def make_model_consistent(model): - x = model.x - xdot = model.xdot - u = model.u - z = model.z - p = model.p - - if isinstance(x, MX): - symbol = MX.sym - elif isinstance(x, SX): - symbol = SX.sym - else: - raise Exception("model.x must be casadi.SX or casadi.MX, got {}".format(type(x))) - - if is_empty(p): - model.p = symbol('p', 0, 0) - - if is_empty(z): - model.z = symbol('z', 0, 0) - - return model - -def get_lib_ext(): - lib_ext = '.so' - if sys.platform == 'darwin': - lib_ext = '.dylib' - elif os.name == 'nt': - lib_ext = '' - - return lib_ext - -def get_tera(): - tera_path = get_tera_exec_path() - acados_path = get_acados_path() - - if os.path.exists(tera_path) and os.access(tera_path, os.X_OK): - return tera_path - - repo_url = "https://github.com/acados/tera_renderer/releases" - url = "{}/download/v{}/t_renderer-v{}-{}".format( - repo_url, TERA_VERSION, TERA_VERSION, PLATFORM2TERA[sys.platform]) - - manual_install = 'For manual installation follow these instructions:\n' - manual_install += '1 Download binaries from {}\n'.format(url) - manual_install += '2 Copy them in {}/bin\n'.format(acados_path) - manual_install += '3 Strip the version and platform from the binaries: ' - manual_install += 'as t_renderer-v0.0.34-X -> t_renderer)\n' - manual_install += '4 Enable execution privilege on the file "t_renderer" with:\n' - manual_install += '"chmod +x {}"\n\n'.format(tera_path) - - msg = "\n" - msg += 'Tera template render executable not found, ' - msg += 'while looking in path:\n{}\n'.format(tera_path) - msg += 'In order to be able to render the templates, ' - msg += 'you need to download the tera renderer binaries from:\n' - msg += '{}\n\n'.format(repo_url) - msg += 'Do you wish to set up Tera renderer automatically?\n' - msg += 'y/N? (press y to download tera or any key for manual installation)\n' - - if input(msg) == 'y': - print("Dowloading {}".format(url)) - with urllib.request.urlopen(url) as response, open(tera_path, 'wb') as out_file: - shutil.copyfileobj(response, out_file) - print("Successfully downloaded t_renderer.") - os.chmod(tera_path, 0o755) - return tera_path - - msg_cancel = "\nYou cancelled automatic download.\n\n" - msg_cancel += manual_install - msg_cancel += "Once installed re-run your script.\n\n" - print(msg_cancel) - - sys.exit(1) - - -def render_template(in_file, out_file, output_dir, json_path, template_glob=None): - - acados_path = os.path.dirname(os.path.abspath(__file__)) - if template_glob is None: - template_glob = os.path.join(acados_path, 'c_templates_tera', '**', '*') - cwd = os.getcwd() - - if not os.path.exists(output_dir): - os.makedirs(output_dir) - os.chdir(output_dir) - - tera_path = get_tera() - - # call tera as system cmd - os_cmd = f"{tera_path} '{template_glob}' '{in_file}' '{json_path}' '{out_file}'" - # Windows cmd.exe can not cope with '...', so use "..." instead: - if os.name == 'nt': - os_cmd = os_cmd.replace('\'', '\"') - - status = os.system(os_cmd) - if (status != 0): - raise Exception(f'Rendering of {in_file} failed!\n\nAttempted to execute OS command:\n{os_cmd}\n\n') - - os.chdir(cwd) - - -## Conversion functions -def make_object_json_dumpable(input): - if isinstance(input, (np.ndarray)): - return input.tolist() - elif isinstance(input, (SX)): - return input.serialize() - elif isinstance(input, (MX)): - # NOTE: MX expressions can not be serialized, only Functions. - return input.__str__() - elif isinstance(input, (DM)): - return input.full() - else: - raise TypeError(f"Cannot make input of type {type(input)} dumpable.") - - -def format_class_dict(d): - """ - removes the __ artifact from class to dict conversion - """ - out = {} - for k, v in d.items(): - if isinstance(v, dict): - v = format_class_dict(v) - - out_key = k.split('__', 1)[-1] - out[k.replace(k, out_key)] = v - return out - - -def get_ocp_nlp_layout() -> dict: - python_interface_path = get_python_interface_path() - abs_path = os.path.join(python_interface_path, 'acados_layout.json') - with open(abs_path, 'r') as f: - ocp_nlp_layout = json.load(f) - return ocp_nlp_layout - - -def get_default_simulink_opts() -> dict: - python_interface_path = get_python_interface_path() - abs_path = os.path.join(python_interface_path, 'simulink_default_opts.json') - with open(abs_path, 'r') as f: - simulink_opts = json.load(f) - return simulink_opts - - -def J_to_idx(J): - nrows = J.shape[0] - idx = np.zeros((nrows, )) - for i in range(nrows): - this_idx = np.nonzero(J[i,:])[0] - if len(this_idx) != 1: - raise Exception('Invalid J matrix structure detected, ' \ - 'must contain one nonzero element per row.') - if this_idx.size > 0 and J[i,this_idx[0]] != 1: - raise Exception('J matrices can only contain 1s.') - idx[i] = this_idx[0] - return idx - - -def J_to_idx_slack(J): - nrows = J.shape[0] - ncol = J.shape[1] - idx = np.zeros((ncol, )) - i_idx = 0 - for i in range(nrows): - this_idx = np.nonzero(J[i,:])[0] - if len(this_idx) == 1: - idx[i_idx] = i - i_idx = i_idx + 1 - elif len(this_idx) > 1: - raise Exception('J_to_idx_slack: Invalid J matrix. ' \ - 'Found more than one nonzero in row ' + str(i)) - if this_idx.size > 0 and J[i,this_idx[0]] != 1: - raise Exception('J_to_idx_slack: J matrices can only contain 1s, ' \ - 'got J(' + str(i) + ', ' + str(this_idx[0]) + ') = ' + str(J[i,this_idx[0]]) ) - if not i_idx == ncol: - raise Exception('J_to_idx_slack: J must contain a 1 in every column!') - return idx - - -def acados_dae_model_json_dump(model): - - # load model - x = model.x - xdot = model.xdot - u = model.u - z = model.z - p = model.p - - f_impl = model.f_impl_expr - model_name = model.name - - # create struct with impl_dae_fun, casadi_version - fun_name = model_name + '_impl_dae_fun' - impl_dae_fun = Function(fun_name, [x, xdot, u, z, p], [f_impl]) - - casadi_version = CasadiMeta.version() - str_impl_dae_fun = impl_dae_fun.serialize() - - dae_dict = {"str_impl_dae_fun": str_impl_dae_fun, "casadi_version": casadi_version} - - # dump - json_file = model_name + '_acados_dae.json' - with open(json_file, 'w') as f: - json.dump(dae_dict, f, default=make_object_json_dumpable, indent=4, sort_keys=True) - print("dumped ", model_name, " dae to file:", json_file, "\n") - - -def set_up_imported_gnsf_model(acados_ocp): - - gnsf = acados_ocp.gnsf_model - - # check CasADi version - # dump_casadi_version = gnsf['casadi_version'] - # casadi_version = CasadiMeta.version() - - # if not casadi_version == dump_casadi_version: - # print("WARNING: GNSF model was dumped with another CasADi version.\n" - # + "This might yield errors. Please use the same version for compatibility, serialize version: " - # + dump_casadi_version + " current Python CasADi verison: " + casadi_version) - # input("Press any key to attempt to continue...") - - # load model - phi_fun = Function.deserialize(gnsf['phi_fun']) - phi_fun_jac_y = Function.deserialize(gnsf['phi_fun_jac_y']) - phi_jac_y_uhat = Function.deserialize(gnsf['phi_jac_y_uhat']) - get_matrices_fun = Function.deserialize(gnsf['get_matrices_fun']) - - # obtain gnsf dimensions - size_gnsf_A = get_matrices_fun.size_out(0) - acados_ocp.dims.gnsf_nx1 = size_gnsf_A[1] - acados_ocp.dims.gnsf_nz1 = size_gnsf_A[0] - size_gnsf_A[1] - acados_ocp.dims.gnsf_nuhat = max(phi_fun.size_in(1)) - acados_ocp.dims.gnsf_ny = max(phi_fun.size_in(0)) - acados_ocp.dims.gnsf_nout = max(phi_fun.size_out(0)) - - # save gnsf functions in model - acados_ocp.model.phi_fun = phi_fun - acados_ocp.model.phi_fun_jac_y = phi_fun_jac_y - acados_ocp.model.phi_jac_y_uhat = phi_jac_y_uhat - acados_ocp.model.get_matrices_fun = get_matrices_fun - - # get_matrices_fun = Function([model_name,'_gnsf_get_matrices_fun'], {dummy},... - # {A, B, C, E, L_x, L_xdot, L_z, L_u, A_LO, c, E_LO, B_LO,... - # nontrivial_f_LO, purely_linear, ipiv_x, ipiv_z, c_LO}); - get_matrices_out = get_matrices_fun(0) - acados_ocp.model.gnsf['nontrivial_f_LO'] = int(get_matrices_out[12]) - acados_ocp.model.gnsf['purely_linear'] = int(get_matrices_out[13]) - - if "f_lo_fun_jac_x1k1uz" in gnsf: - f_lo_fun_jac_x1k1uz = Function.deserialize(gnsf['f_lo_fun_jac_x1k1uz']) - acados_ocp.model.f_lo_fun_jac_x1k1uz = f_lo_fun_jac_x1k1uz - else: - dummy_var_x1 = SX.sym('dummy_var_x1', acados_ocp.dims.gnsf_nx1) - dummy_var_x1dot = SX.sym('dummy_var_x1dot', acados_ocp.dims.gnsf_nx1) - dummy_var_z1 = SX.sym('dummy_var_z1', acados_ocp.dims.gnsf_nz1) - dummy_var_u = SX.sym('dummy_var_z1', acados_ocp.dims.nu) - dummy_var_p = SX.sym('dummy_var_z1', acados_ocp.dims.np) - empty_var = SX.sym('empty_var', 0, 0) - - empty_fun = Function('empty_fun', \ - [dummy_var_x1, dummy_var_x1dot, dummy_var_z1, dummy_var_u, dummy_var_p], - [empty_var]) - acados_ocp.model.f_lo_fun_jac_x1k1uz = empty_fun - - del acados_ocp.gnsf_model - - -def idx_perm_to_ipiv(idx_perm): - n = len(idx_perm) - vec = list(range(n)) - ipiv = np.zeros(n) - - print(n, idx_perm) - # import pdb; pdb.set_trace() - for ii in range(n): - idx0 = idx_perm[ii] - for jj in range(ii,n): - if vec[jj]==idx0: - idx1 = jj - break - tmp = vec[ii] - vec[ii] = vec[idx1] - vec[idx1] = tmp - ipiv[ii] = idx1 - - ipiv = ipiv-1 # C 0-based indexing - return ipiv - - -def print_casadi_expression(f): - for ii in range(casadi_length(f)): - print(f[ii,:]) diff --git a/third_party/acados/acados_template/zoro_description.py b/third_party/acados/acados_template/zoro_description.py deleted file mode 100644 index 4d795c1502..0000000000 --- a/third_party/acados/acados_template/zoro_description.py +++ /dev/null @@ -1,78 +0,0 @@ -# Copyright (c) The acados authors. -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; - -from dataclasses import dataclass, field -import numpy as np - - -@dataclass -class ZoroDescription: - """ - Zero-Order Robust Optimization scheme. - - For advanced users. - """ - backoff_scaling_gamma: float = 1.0 - fdbk_K_mat: np.ndarray = None - unc_jac_G_mat: np.ndarray = None # default: an identity matrix - P0_mat: np.ndarray = None - W_mat: np.ndarray = None - idx_lbx_t: list = field(default_factory=list) - idx_ubx_t: list = field(default_factory=list) - idx_lbx_e_t: list = field(default_factory=list) - idx_ubx_e_t: list = field(default_factory=list) - idx_lbu_t: list = field(default_factory=list) - idx_ubu_t: list = field(default_factory=list) - idx_lg_t: list = field(default_factory=list) - idx_ug_t: list = field(default_factory=list) - idx_lg_e_t: list = field(default_factory=list) - idx_ug_e_t: list = field(default_factory=list) - idx_lh_t: list = field(default_factory=list) - idx_uh_t: list = field(default_factory=list) - idx_lh_e_t: list = field(default_factory=list) - idx_uh_e_t: list = field(default_factory=list) - -def process_zoro_description(zoro_description: ZoroDescription): - zoro_description.nw, _ = zoro_description.W_mat.shape - if zoro_description.unc_jac_G_mat is None: - zoro_description.unc_jac_G_mat = np.eye(zoro_description.nw) - zoro_description.nlbx_t = len(zoro_description.idx_lbx_t) - zoro_description.nubx_t = len(zoro_description.idx_ubx_t) - zoro_description.nlbx_e_t = len(zoro_description.idx_lbx_e_t) - zoro_description.nubx_e_t = len(zoro_description.idx_ubx_e_t) - zoro_description.nlbu_t = len(zoro_description.idx_lbu_t) - zoro_description.nubu_t = len(zoro_description.idx_ubu_t) - zoro_description.nlg_t = len(zoro_description.idx_lg_t) - zoro_description.nug_t = len(zoro_description.idx_ug_t) - zoro_description.nlg_e_t = len(zoro_description.idx_lg_e_t) - zoro_description.nug_e_t = len(zoro_description.idx_ug_e_t) - zoro_description.nlh_t = len(zoro_description.idx_lh_t) - zoro_description.nuh_t = len(zoro_description.idx_uh_t) - zoro_description.nlh_e_t = len(zoro_description.idx_lh_e_t) - zoro_description.nuh_e_t = len(zoro_description.idx_uh_e_t) - return zoro_description.__dict__ diff --git a/third_party/acados/build.sh b/third_party/acados/build.sh deleted file mode 100755 index 95b3913c4a..0000000000 --- a/third_party/acados/build.sh +++ /dev/null @@ -1,64 +0,0 @@ -#!/usr/bin/env bash -set -e - -export SOURCE_DATE_EPOCH=0 -export ZERO_AR_DATE=1 - -DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" - -ARCHNAME="x86_64" -BLAS_TARGET="X64_AUTOMATIC" -if [ -f /TICI ]; then - ARCHNAME="larch64" - BLAS_TARGET="ARMV8A_ARM_CORTEX_A57" -fi - -ACADOS_FLAGS="-DACADOS_WITH_QPOASES=ON -UBLASFEO_TARGET -DBLASFEO_TARGET=$BLAS_TARGET" - -if [[ "$OSTYPE" == "darwin"* ]]; then - ACADOS_FLAGS="$ACADOS_FLAGS -DCMAKE_OSX_ARCHITECTURES=arm64 -DCMAKE_MACOSX_RPATH=1" - ARCHNAME="Darwin" -fi - -if [ ! -d acados_repo/ ]; then - git clone https://github.com/acados/acados.git $DIR/acados_repo - # git clone https://github.com/commaai/acados.git $DIR/acados_repo -fi -cd acados_repo -git fetch --all -git checkout 8af9b0ad180940ef611884574a0b27a43504311d # v0.2.2 -git submodule update --depth=1 --recursive --init - -# build -mkdir -p build -cd build -cmake $ACADOS_FLAGS .. -make -j20 install - -INSTALL_DIR="$DIR/$ARCHNAME" -rm -rf $INSTALL_DIR -mkdir -p $INSTALL_DIR - -rm $DIR/acados_repo/lib/*.json - -rm -rf $DIR/include $DIR/acados_template -cp -r $DIR/acados_repo/include $DIR -cp -r $DIR/acados_repo/lib $INSTALL_DIR -cp -r $DIR/acados_repo/interfaces/acados_template/acados_template $DIR/ -#pip3 install -e $DIR/acados/interfaces/acados_template - -# skip macOS - sed is different :/ -if [[ "$OSTYPE" != "darwin"* ]]; then - # strip future_fstrings to avoid having to install the compatibility package - find $DIR/acados_template/ -type f -exec sed -i '/future.fstrings/d' {} + -fi - -# build tera -cd $DIR/acados_repo/interfaces/acados_template/tera_renderer/ -if [[ "$OSTYPE" == "darwin"* ]]; then - cargo build --verbose --release --target aarch64-apple-darwin - cp target/aarch64-apple-darwin/release/t_renderer target/release/t_renderer -else - cargo build --verbose --release -fi -cp target/release/t_renderer $INSTALL_DIR/ diff --git a/third_party/acados/include/acados/dense_qp/dense_qp_common.h b/third_party/acados/include/acados/dense_qp/dense_qp_common.h deleted file mode 100644 index 2a9a974f99..0000000000 --- a/third_party/acados/include/acados/dense_qp/dense_qp_common.h +++ /dev/null @@ -1,147 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_DENSE_QP_DENSE_QP_COMMON_H_ -#define ACADOS_DENSE_QP_DENSE_QP_COMMON_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// hpipm -#include "hpipm/include/hpipm_d_dense_qp.h" -#include "hpipm/include/hpipm_d_dense_qp_res.h" -#include "hpipm/include/hpipm_d_dense_qp_sol.h" -// acados -#include "acados/utils/types.h" - -typedef struct d_dense_qp_dim dense_qp_dims; -typedef struct d_dense_qp dense_qp_in; -typedef struct d_dense_qp_sol dense_qp_out; -typedef struct d_dense_qp_res dense_qp_res; -typedef struct d_dense_qp_res_ws dense_qp_res_ws; - - - -#ifndef QP_SOLVER_CONFIG_ -#define QP_SOLVER_CONFIG_ -typedef struct -{ - void (*dims_set)(void *config_, void *dims_, const char *field, const int* value); - acados_size_t (*opts_calculate_size)(void *config, void *dims); - void *(*opts_assign)(void *config, void *dims, void *raw_memory); - void (*opts_initialize_default)(void *config, void *dims, void *args); - void (*opts_update)(void *config, void *dims, void *args); - void (*opts_set)(void *config_, void *opts_, const char *field, void* value); - acados_size_t (*memory_calculate_size)(void *config, void *dims, void *args); - void *(*memory_assign)(void *config, void *dims, void *args, void *raw_memory); - void (*memory_get)(void *config_, void *mem_, const char *field, void* value); - acados_size_t (*workspace_calculate_size)(void *config, void *dims, void *args); - int (*evaluate)(void *config, void *qp_in, void *qp_out, void *args, void *mem, void *work); - void (*eval_sens)(void *config, void *qp_in, void *qp_out, void *opts, void *mem, void *work); -} qp_solver_config; -#endif - - - -#ifndef QP_INFO_ -#define QP_INFO_ -typedef struct -{ - double solve_QP_time; - double condensing_time; - double interface_time; - double total_time; - int num_iter; - int t_computed; -} qp_info; -#endif - - - -/* config */ -// -acados_size_t dense_qp_solver_config_calculate_size(); -// -qp_solver_config *dense_qp_solver_config_assign(void *raw_memory); - -/* dims */ -// -acados_size_t dense_qp_dims_calculate_size(); -// -dense_qp_dims *dense_qp_dims_assign(void *raw_memory); -// -void dense_qp_dims_set(void *config_, void *dims_, const char *field, const int* value); -// - -/* in */ -// -acados_size_t dense_qp_in_calculate_size(dense_qp_dims *dims); -// -dense_qp_in *dense_qp_in_assign(dense_qp_dims *dims, void *raw_memory); - -/* out */ -// -acados_size_t dense_qp_out_calculate_size(dense_qp_dims *dims); -// -dense_qp_out *dense_qp_out_assign(dense_qp_dims *dims, void *raw_memory); -// -void dense_qp_out_get(dense_qp_out *out, const char *field, void *value); - -/* res */ -// -acados_size_t dense_qp_res_calculate_size(dense_qp_dims *dims); -// -dense_qp_res *dense_qp_res_assign(dense_qp_dims *dims, void *raw_memory); -// -acados_size_t dense_qp_res_workspace_calculate_size(dense_qp_dims *dims); -// -dense_qp_res_ws *dense_qp_res_workspace_assign(dense_qp_dims *dims, void *raw_memory); -// -void dense_qp_compute_t(dense_qp_in *qp_in, dense_qp_out *qp_out); -// -void dense_qp_res_compute(dense_qp_in *qp_in, dense_qp_out *qp_out, dense_qp_res *qp_res, dense_qp_res_ws *res_ws); -// -void dense_qp_res_compute_nrm_inf(dense_qp_res *qp_res, double res[4]); - -/* misc */ -// -void dense_qp_stack_slacks_dims(dense_qp_dims *in, dense_qp_dims *out); -// -void dense_qp_stack_slacks(dense_qp_in *in, dense_qp_in *out); -// -void dense_qp_unstack_slacks(dense_qp_out *in, dense_qp_in *qp_out, dense_qp_out *out); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_DENSE_QP_DENSE_QP_COMMON_H_ diff --git a/third_party/acados/include/acados/dense_qp/dense_qp_daqp.h b/third_party/acados/include/acados/dense_qp/dense_qp_daqp.h deleted file mode 100644 index b262089b4f..0000000000 --- a/third_party/acados/include/acados/dense_qp/dense_qp_daqp.h +++ /dev/null @@ -1,110 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_DENSE_QP_DENSE_QP_DAQP_H_ -#define ACADOS_DENSE_QP_DENSE_QP_DAQP_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// blasfeo -#include "blasfeo/include/blasfeo_common.h" - -// daqp -#include "daqp/include/types.h" - -// acados -#include "acados/dense_qp/dense_qp_common.h" -#include "acados/utils/types.h" - - -typedef struct dense_qp_daqp_opts_ -{ - DAQPSettings* daqp_opts; - int warm_start; -} dense_qp_daqp_opts; - - -typedef struct dense_qp_daqp_memory_ -{ - double* lb_tmp; - double* ub_tmp; - int* idxb; - int* idxv_to_idxb; - int* idxs; - int* idxdaqp_to_idxs; - - double* Zl; - double* Zu; - double* zl; - double* zu; - double* d_ls; - double* d_us; - - double time_qp_solver_call; - int iter; - DAQPWorkspace * daqp_work; - -} dense_qp_daqp_memory; - -// opts -acados_size_t dense_qp_daqp_opts_calculate_size(void *config, dense_qp_dims *dims); -// -void *dense_qp_daqp_opts_assign(void *config, dense_qp_dims *dims, void *raw_memory); -// -void dense_qp_daqp_opts_initialize_default(void *config, dense_qp_dims *dims, void *opts_); -// -void dense_qp_daqp_opts_update(void *config, dense_qp_dims *dims, void *opts_); -// -// memory -acados_size_t dense_qp_daqp_workspace_calculate_size(void *config, dense_qp_dims *dims, void *opts_); -// -void *dense_qp_daqp_workspace_assign(void *config, dense_qp_dims *dims, void *raw_memory); -// -acados_size_t dense_qp_daqp_memory_calculate_size(void *config, dense_qp_dims *dims, void *opts_); -// -void *dense_qp_daqp_memory_assign(void *config, dense_qp_dims *dims, void *opts_, void *raw_memory); -// -// functions -int dense_qp_daqp(void *config, dense_qp_in *qp_in, dense_qp_out *qp_out, void *opts_, void *memory_, void *work_); -// -void dense_qp_daqp_eval_sens(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void dense_qp_daqp_memory_reset(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void dense_qp_daqp_config_initialize_default(void *config_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_DENSE_QP_DENSE_QP_DAQP_H_ diff --git a/third_party/acados/include/acados/dense_qp/dense_qp_hpipm.h b/third_party/acados/include/acados/dense_qp/dense_qp_hpipm.h deleted file mode 100644 index 136279d666..0000000000 --- a/third_party/acados/include/acados/dense_qp/dense_qp_hpipm.h +++ /dev/null @@ -1,91 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_DENSE_QP_DENSE_QP_HPIPM_H_ -#define ACADOS_DENSE_QP_DENSE_QP_HPIPM_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// hpipm -#include "hpipm/include/hpipm_d_dense_qp.h" -#include "hpipm/include/hpipm_d_dense_qp_ipm.h" -#include "hpipm/include/hpipm_d_dense_qp_sol.h" -// acados -#include "acados/dense_qp/dense_qp_common.h" -#include "acados/utils/types.h" - - - -typedef struct dense_qp_hpipm_opts_ -{ - struct d_dense_qp_ipm_arg *hpipm_opts; -} dense_qp_hpipm_opts; - - - -typedef struct dense_qp_hpipm_memory_ -{ - struct d_dense_qp_ipm_ws *hpipm_workspace; - double time_qp_solver_call; - int iter; - -} dense_qp_hpipm_memory; - - - -// -acados_size_t dense_qp_hpipm_opts_calculate_size(void *config, void *dims); -// -void *dense_qp_hpipm_opts_assign(void *config, void *dims, void *raw_memory); -// -void dense_qp_hpipm_opts_initialize_default(void *config, void *dims, void *opts_); -// -void dense_qp_hpipm_opts_update(void *config, void *dims, void *opts_); -// -acados_size_t dense_qp_hpipm_calculate_memory_size(void *dims, void *opts_); -// -void *dense_qp_hpipm_assign_memory(void *dims, void *opts_, void *raw_memory); -// -acados_size_t dense_qp_hpipm_calculate_workspace_size(void *dims, void *opts_); -// -int dense_qp_hpipm(void *config, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void dense_qp_hpipm_eval_sens(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void dense_qp_hpipm_config_initialize_default(void *config_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_DENSE_QP_DENSE_QP_HPIPM_H_ diff --git a/third_party/acados/include/acados/dense_qp/dense_qp_ooqp.h b/third_party/acados/include/acados/dense_qp/dense_qp_ooqp.h deleted file mode 100644 index d051cb15f7..0000000000 --- a/third_party/acados/include/acados/dense_qp/dense_qp_ooqp.h +++ /dev/null @@ -1,125 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_DENSE_QP_DENSE_QP_OOQP_H_ -#define ACADOS_DENSE_QP_DENSE_QP_OOQP_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/dense_qp/dense_qp_common.h" -#include "acados/utils/types.h" - -enum dense_qp_ooqp_termination_code -{ - DENSE_SUCCESSFUL_TERMINATION = 0, - DENSE_NOT_FINISHED, - DENSE_MAX_ITS_EXCEEDED, - DENSE_INFEASIBLE, - DENSE_UNKNOWN -}; - -typedef struct dense_qp_ooqp_opts_ -{ - int printLevel; - int useDiagonalWeights; // TODO(dimitris): implement option - int fixHessian; - int fixDynamics; - int fixInequalities; -} dense_qp_ooqp_opts; - -typedef struct dense_qp_ooqp_workspace_ -{ - double *x; - double *gamma; - double *phi; - double *y; - double *z; - double *lambda; - double *pi; - double objectiveValue; -} dense_qp_ooqp_workspace; - -typedef struct dense_qp_ooqp_memory_ -{ - int firstRun; - int nx; - int my; - int mz; - double *c; - double *dQ; - double *xlow; - char *ixlow; - double *xupp; - char *ixupp; - double *dA; - double *bA; - double *dC; - double *clow; - char *iclow; - double *cupp; - char *icupp; - double time_qp_solver_call; - int iter; - -} dense_qp_ooqp_memory; - -// -acados_size_t dense_qp_ooqp_opts_calculate_size(void *config_, dense_qp_dims *dims); -// -void *dense_qp_ooqp_opts_assign(void *config_, dense_qp_dims *dims, void *raw_memory); -// -void dense_qp_ooqp_opts_initialize_default(void *config_, dense_qp_dims *dims, void *opts_); -// -void dense_qp_ooqp_opts_update(void *config_, dense_qp_dims *dims, void *opts_); -// -acados_size_t dense_qp_ooqp_memory_calculate_size(void *config_, dense_qp_dims *dims, void *opts_); -// -void *dense_qp_ooqp_memory_assign(void *config_, dense_qp_dims *dims, void *opts_, - void *raw_memory); -// -acados_size_t dense_qp_ooqp_workspace_calculate_size(void *config_, dense_qp_dims *dims, void *opts_); -// -int dense_qp_ooqp(void *config_, dense_qp_in *qp_in, dense_qp_out *qp_out, void *opts_, - void *memory_, void *work_); -// -void dense_qp_ooqp_destroy(void *mem_, void *work); -// -void dense_qp_ooqp_eval_sens(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void dense_qp_ooqp_config_initialize_default(void *config_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_DENSE_QP_DENSE_QP_OOQP_H_ diff --git a/third_party/acados/include/acados/dense_qp/dense_qp_qore.h b/third_party/acados/include/acados/dense_qp/dense_qp_qore.h deleted file mode 100644 index 392e472918..0000000000 --- a/third_party/acados/include/acados/dense_qp/dense_qp_qore.h +++ /dev/null @@ -1,124 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_DENSE_QP_DENSE_QP_QORE_H_ -#define ACADOS_DENSE_QP_DENSE_QP_QORE_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// qore -#include "qore/QPSOLVER_DENSE/include/qpsolver_dense.h" -// acados -#include "acados/dense_qp/dense_qp_common.h" -#include "acados/utils/types.h" - -typedef struct dense_qp_qore_opts_ -{ - int nsmax; // maximum size of Schur complement - int print_freq; // print frequency, - // prtfreq < 0: disable printing; - // prtfreq == 0: print on each call and include working set changes; - // prtfreq > 0: print on every prtfreq seconds, but do not include working set - // changes; - int warm_start; // warm start with updated matrices H and C - int warm_strategy; // 0: ramp-up from zero homotopy; 1: setup homotopy from the previous - // solution - int hot_start; // hot start with unchanged matrices H and C - int max_iter; // maximum number of iterations - int compute_t; // compute t in qp_out (to have correct residuals in NLP) -} dense_qp_qore_opts; - -typedef struct dense_qp_qore_memory_ -{ - double *H; - double *HH; - double *g; - double *gg; - double *Zl; - double *Zu; - double *zl; - double *zu; - double *A; - double *b; - double *C; - double *CC; - double *Ct; - double *CCt; - double *d_lb0; - double *d_ub0; - double *d_lb; - double *d_ub; - double *d_lg; - double *d_ug; - double *d_ls; - double *d_us; - double *lb; - double *ub; - int *idxb; - int *idxb_stacked; - int *idxs; - double *prim_sol; - double *dual_sol; - QoreProblemDense *QP; - int num_iter; - dense_qp_in *qp_stacked; - double time_qp_solver_call; - int iter; - -} dense_qp_qore_memory; - -acados_size_t dense_qp_qore_opts_calculate_size(void *config, dense_qp_dims *dims); -// -void *dense_qp_qore_opts_assign(void *config, dense_qp_dims *dims, void *raw_memory); -// -void dense_qp_qore_opts_initialize_default(void *config, dense_qp_dims *dims, void *opts_); -// -void dense_qp_qore_opts_update(void *config, dense_qp_dims *dims, void *opts_); -// -acados_size_t dense_qp_qore_memory_calculate_size(void *config, dense_qp_dims *dims, void *opts_); -// -void *dense_qp_qore_memory_assign(void *config, dense_qp_dims *dims, void *opts_, void *raw_memory); -// -acados_size_t dense_qp_qore_workspace_calculate_size(void *config, dense_qp_dims *dims, void *opts_); -// -int dense_qp_qore(void *config, dense_qp_in *qp_in, dense_qp_out *qp_out, void *opts_, void *memory_, void *work_); -// -void dense_qp_qore_eval_sens(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void dense_qp_qore_config_initialize_default(void *config); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_DENSE_QP_DENSE_QP_QORE_H_ diff --git a/third_party/acados/include/acados/dense_qp/dense_qp_qpoases.h b/third_party/acados/include/acados/dense_qp/dense_qp_qpoases.h deleted file mode 100644 index 0e13d3ef64..0000000000 --- a/third_party/acados/include/acados/dense_qp/dense_qp_qpoases.h +++ /dev/null @@ -1,126 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_DENSE_QP_DENSE_QP_QPOASES_H_ -#define ACADOS_DENSE_QP_DENSE_QP_QPOASES_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// blasfeo -#include "blasfeo/include/blasfeo_common.h" - -// acados -#include "acados/dense_qp/dense_qp_common.h" -#include "acados/utils/types.h" - -typedef struct dense_qp_qpoases_opts_ -{ - double max_cputime; // maximum cpu time in seconds - int max_nwsr; // maximum number of working set recalculations - int warm_start; // warm start with dual_sol in memory - int use_precomputed_cholesky; - int hotstart; // this option requires constant data matrices! (eg linear MPC, inexact schemes - // with frozen sensitivities) - int set_acado_opts; // use same options as in acado code generation - int compute_t; // compute t in qp_out (to have correct residuals in NLP) - double tolerance; // terminationTolerance -} dense_qp_qpoases_opts; - -typedef struct dense_qp_qpoases_memory_ -{ - double *H; - double *HH; - double *R; - double *g; - double *gg; - double *Zl; - double *Zu; - double *zl; - double *zu; - double *A; - double *b; - double *d_lb0; - double *d_ub0; - double *d_lb; - double *d_ub; - double *C; - double *CC; - double *d_lg0; - double *d_ug0; - double *d_lg; - double *d_ug; - double *d_ls; - double *d_us; - int *idxb; - int *idxb_stacked; - int *idxs; - double *prim_sol; - double *dual_sol; - void *QPB; // NOTE(giaf): cast to QProblemB to use - void *QP; // NOTE(giaf): cast to QProblem to use - double cputime; // cputime of qpoases - int nwsr; // performed number of working set recalculations - int first_it; // to be used with hotstart - dense_qp_in *qp_stacked; - double time_qp_solver_call; // equal to cputime - int iter; - -} dense_qp_qpoases_memory; - -acados_size_t dense_qp_qpoases_opts_calculate_size(void *config, dense_qp_dims *dims); -// -void *dense_qp_qpoases_opts_assign(void *config, dense_qp_dims *dims, void *raw_memory); -// -void dense_qp_qpoases_opts_initialize_default(void *config, dense_qp_dims *dims, void *opts_); -// -void dense_qp_qpoases_opts_update(void *config, dense_qp_dims *dims, void *opts_); -// -acados_size_t dense_qp_qpoases__memorycalculate_size(void *config, dense_qp_dims *dims, void *opts_); -// -void *dense_qp_qpoases_memory_assign(void *config, dense_qp_dims *dims, void *opts_, void *raw_memory); -// -acados_size_t dense_qp_qpoases_workspace_calculate_size(void *config, dense_qp_dims *dims, void *opts_); -// -int dense_qp_qpoases(void *config, dense_qp_in *qp_in, dense_qp_out *qp_out, void *opts_, void *memory_, void *work_); -// -void dense_qp_qpoases_eval_sens(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void dense_qp_qpoases_memory_reset(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void dense_qp_qpoases_config_initialize_default(void *config_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_DENSE_QP_DENSE_QP_QPOASES_H_ diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_common.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_common.h deleted file mode 100644 index ba97db9768..0000000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_common.h +++ /dev/null @@ -1,446 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - - -/// \defgroup ocp_nlp ocp_nlp -/// @{ -/// @} - -/// \defgroup ocp_nlp_solver ocp_nlp_solver -/// @{ -/// @} - -/// \ingroup ocp_nlp -/// @{ - -/// \ingroup ocp_nlp_solver -/// @{ - -/// \defgroup ocp_nlp_common ocp_nlp_common -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_COMMON_H_ -#define ACADOS_OCP_NLP_OCP_NLP_COMMON_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/ocp_nlp/ocp_nlp_constraints_common.h" -#include "acados/ocp_nlp/ocp_nlp_cost_common.h" -#include "acados/ocp_nlp/ocp_nlp_dynamics_common.h" -#include "acados/ocp_nlp/ocp_nlp_reg_common.h" -#include "acados/ocp_qp/ocp_qp_common.h" -#include "acados/ocp_qp/ocp_qp_xcond_solver.h" -#include "acados/sim/sim_common.h" -#include "acados/utils/external_function_generic.h" -#include "acados/utils/types.h" - - - -/************************************************ - * config - ************************************************/ - -typedef struct ocp_nlp_config -{ - int N; // number of stages - - // solver-specific implementations of memory management functions - acados_size_t (*opts_calculate_size)(void *config, void *dims); - void *(*opts_assign)(void *config, void *dims, void *raw_memory); - void (*opts_initialize_default)(void *config, void *dims, void *opts_); - void (*opts_update)(void *config, void *dims, void *opts_); - acados_size_t (*memory_calculate_size)(void *config, void *dims, void *opts_); - void *(*memory_assign)(void *config, void *dims, void *opts_, void *raw_memory); - acados_size_t (*workspace_calculate_size)(void *config, void *dims, void *opts_); - void (*opts_set)(void *config_, void *opts_, const char *field, void* value); - void (*opts_set_at_stage)(void *config_, void *opts_, size_t stage, const char *field, void* value); - // evaluate solver // TODO rename into solve - int (*evaluate)(void *config, void *dims, void *nlp_in, void *nlp_out, void *opts_, void *mem, void *work); - void (*eval_param_sens)(void *config, void *dims, void *opts_, void *mem, void *work, - char *field, int stage, int index, void *sens_nlp_out); - // prepare memory - int (*precompute)(void *config, void *dims, void *nlp_in, void *nlp_out, void *opts_, void *mem, void *work); - void (*memory_reset_qp_solver)(void *config, void *dims, void *nlp_in, void *nlp_out, void *opts_, void *mem, void *work); - // initalize this struct with default values - void (*config_initialize_default)(void *config); - // general getter - void (*get)(void *config_, void *dims, void *mem_, const char *field, void *return_value_); - void (*opts_get)(void *config_, void *dims, void *opts_, const char *field, void *return_value_); - void (*work_get)(void *config_, void *dims, void *work_, const char *field, void *return_value_); - // config structs of submodules - ocp_qp_xcond_solver_config *qp_solver; // TODO rename xcond_solver - ocp_nlp_dynamics_config **dynamics; - ocp_nlp_cost_config **cost; - ocp_nlp_constraints_config **constraints; - ocp_nlp_reg_config *regularize; - -} ocp_nlp_config; - -// -acados_size_t ocp_nlp_config_calculate_size(int N); -// -ocp_nlp_config *ocp_nlp_config_assign(int N, void *raw_memory); - - - -/************************************************ - * dims - ************************************************/ - -/// Structure to store dimensions/number of variables. -typedef struct ocp_nlp_dims -{ - void **cost; - void **dynamics; - void **constraints; - ocp_qp_xcond_solver_dims *qp_solver; // xcond solver instead ?? - ocp_nlp_reg_dims *regularize; - - int *nv; // number of primal variables (states+controls+slacks) - int *nx; // number of differential states - int *nu; // number of inputs - int *ni; // number of two-sided inequality constraints: nb+ng+nh+ns - int *nz; // number of algebraic variables - int *ns; // number of slack variables - int N; // number of shooting nodes - - void *raw_memory; // Pointer to allocated memory, to be used for freeing -} ocp_nlp_dims; - -// -acados_size_t ocp_nlp_dims_calculate_size(void *config); -// -ocp_nlp_dims *ocp_nlp_dims_assign(void *config, void *raw_memory); - -/// Sets the dimension of optimization variables -/// (states, constrols, algebraic variables, slack variables). -/// -/// \param config_ The configuration struct. -/// \param dims_ The dimension struct. -/// \param field The type of optimization variables, either nx, nu, nz, or ns. -/// \param value_array Number of variables for each stage. -void ocp_nlp_dims_set_opt_vars(void *config_, void *dims_, - const char *field, const void* value_array); - -/// Sets the dimensions of constraints functions for a stage -/// (bounds on states, bounds on controls, equality constraints, -/// inequality constraints). -/// -/// \param config_ The configuration struct. -/// \param dims_ The dimension struct. -/// \param stage Stage number. -/// \param field The type of constraint/bound, either nbx, nbu, ng, or nh. -/// \param value_field Number of constraints/bounds for the given stage. -void ocp_nlp_dims_set_constraints(void *config_, void *dims_, int stage, - const char *field, const void* value_field); - -/// Sets the dimensions of the cost terms for a stage. -/// -/// \param config_ The configuration struct. -/// \param dims_ The dimension struct. -/// \param stage Stage number. -/// \param field Type of cost term, can be eiter ny. -/// \param value_field Number of cost terms/residuals for the given stage. -void ocp_nlp_dims_set_cost(void *config_, void *dims_, int stage, const char *field, - const void* value_field); - -/// Sets the dimensions of the dynamics for a stage. -/// -/// \param config_ The configuration struct. -/// \param dims_ The dimension struct. -/// \param stage Stage number. -/// \param field TBD -/// \param value TBD -void ocp_nlp_dims_set_dynamics(void *config_, void *dims_, int stage, const char *field, - const void* value); - -/************************************************ - * Inputs - ************************************************/ - -/// Struct for storing the inputs of an OCP NLP solver -typedef struct ocp_nlp_in -{ - /// Length of sampling intervals/timesteps. - double *Ts; - - /// Pointers to cost functions (TBC). - void **cost; - - /// Pointers to dynamics functions (TBC). - void **dynamics; - - /// Pointers to constraints functions (TBC). - void **constraints; - - /// Pointer to allocated memory, to be used for freeing. - void *raw_memory; - -} ocp_nlp_in; - -// -acados_size_t ocp_nlp_in_calculate_size_self(int N); -// -acados_size_t ocp_nlp_in_calculate_size(ocp_nlp_config *config, ocp_nlp_dims *dims); -// -ocp_nlp_in *ocp_nlp_in_assign_self(int N, void *raw_memory); -// -ocp_nlp_in *ocp_nlp_in_assign(ocp_nlp_config *config, ocp_nlp_dims *dims, void *raw_memory); - - -/************************************************ - * out - ************************************************/ - -typedef struct ocp_nlp_out -{ - struct blasfeo_dvec *ux; // NOTE: this contains [u; x; s_l; s_u]! - rename to uxs? - struct blasfeo_dvec *z; // algebraic vairables - struct blasfeo_dvec *pi; // multipliers for dynamics - struct blasfeo_dvec *lam; // inequality mulitpliers - struct blasfeo_dvec *t; // slack variables corresponding to evaluation of all inequalities (at the solution) - - // NOTE: the inequalities are internally organized in the following order: - // [ lbu lbx lg lh lphi ubu ubx ug uh uphi; lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi] - double inf_norm_res; - - void *raw_memory; // Pointer to allocated memory, to be used for freeing - -} ocp_nlp_out; - -// -acados_size_t ocp_nlp_out_calculate_size(ocp_nlp_config *config, ocp_nlp_dims *dims); -// -ocp_nlp_out *ocp_nlp_out_assign(ocp_nlp_config *config, ocp_nlp_dims *dims, - void *raw_memory); - - - -/************************************************ - * options - ************************************************/ - -/// Globalization types -typedef enum -{ - FIXED_STEP, - MERIT_BACKTRACKING, -} ocp_nlp_globalization_t; - -typedef struct ocp_nlp_opts -{ - ocp_qp_xcond_solver_opts *qp_solver_opts; // xcond solver opts instead ??? - void *regularize; - void **dynamics; // dynamics_opts - void **cost; // cost_opts - void **constraints; // constraints_opts - double step_length; // step length in case of FIXED_STEP - double levenberg_marquardt; // LM factor to be added to the hessian before regularization - int reuse_workspace; - int num_threads; - int print_level; - - // TODO: move to separate struct? - ocp_nlp_globalization_t globalization; - int full_step_dual; - int line_search_use_sufficient_descent; - int globalization_use_SOC; - double alpha_min; - double alpha_reduction; - double eps_sufficient_descent; -} ocp_nlp_opts; - -// -acados_size_t ocp_nlp_opts_calculate_size(void *config, void *dims); -// -void *ocp_nlp_opts_assign(void *config, void *dims, void *raw_memory); -// -void ocp_nlp_opts_initialize_default(void *config, void *dims, void *opts); -// -void ocp_nlp_opts_update(void *config, void *dims, void *opts); -// -void ocp_nlp_opts_set(void *config_, void *opts_, const char *field, void* value); -// -void ocp_nlp_opts_set_at_stage(void *config, void *opts, int stage, const char *field, void *value); - - -/************************************************ - * residuals - ************************************************/ - -typedef struct ocp_nlp_res -{ - struct blasfeo_dvec *res_stat; // stationarity - struct blasfeo_dvec *res_eq; // dynamics - struct blasfeo_dvec *res_ineq; // inequality constraints - struct blasfeo_dvec *res_comp; // complementarity - struct blasfeo_dvec tmp; // tmp - double inf_norm_res_stat; - double inf_norm_res_eq; - double inf_norm_res_ineq; - double inf_norm_res_comp; - acados_size_t memsize; -} ocp_nlp_res; - -// -acados_size_t ocp_nlp_res_calculate_size(ocp_nlp_dims *dims); -// -ocp_nlp_res *ocp_nlp_res_assign(ocp_nlp_dims *dims, void *raw_memory); -// -void ocp_nlp_res_get_inf_norm(ocp_nlp_res *res, double *out); - -/************************************************ - * memory - ************************************************/ - -typedef struct ocp_nlp_memory -{ -// void *qp_solver_mem; // xcond solver mem instead ??? - ocp_qp_xcond_solver_memory *qp_solver_mem; // xcond solver mem instead ??? - void *regularize_mem; - void **dynamics; // dynamics memory - void **cost; // cost memory - void **constraints; // constraints memory - - // residuals - ocp_nlp_res *nlp_res; - - // qp in & out - ocp_qp_in *qp_in; - ocp_qp_out *qp_out; - // QP stuff not entering the qp_in struct - struct blasfeo_dmat *dzduxt; // dzdux transposed - struct blasfeo_dvec *z_alg; // z_alg, output algebraic variables - - struct blasfeo_dvec *cost_grad; - struct blasfeo_dvec *ineq_fun; - struct blasfeo_dvec *ineq_adj; - struct blasfeo_dvec *dyn_fun; - struct blasfeo_dvec *dyn_adj; - - double cost_value; - - bool *set_sim_guess; // indicate if there is new explicitly provided guess for integration variables - struct blasfeo_dvec *sim_guess; - - int *sqp_iter; // pointer to iteration number - -} ocp_nlp_memory; - -// -acados_size_t ocp_nlp_memory_calculate_size(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_opts *opts); -// -ocp_nlp_memory *ocp_nlp_memory_assign(ocp_nlp_config *config, ocp_nlp_dims *dims, - ocp_nlp_opts *opts, void *raw_memory); - - - -/************************************************ - * workspace - ************************************************/ - -typedef struct ocp_nlp_workspace -{ - - void *qp_work; - void **dynamics; // dynamics_workspace - void **cost; // cost_workspace - void **constraints; // constraints_workspace - - // for globalization: -> move to module?! - ocp_nlp_out *tmp_nlp_out; - ocp_nlp_out *weight_merit_fun; - struct blasfeo_dvec tmp_nxu; - struct blasfeo_dvec tmp_ni; - struct blasfeo_dvec dxnext_dy; - -} ocp_nlp_workspace; - -// -acados_size_t ocp_nlp_workspace_calculate_size(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_opts *opts); -// -ocp_nlp_workspace *ocp_nlp_workspace_assign(ocp_nlp_config *config, ocp_nlp_dims *dims, - ocp_nlp_opts *opts, ocp_nlp_memory *mem, void *raw_memory); - - - -/************************************************ - * function - ************************************************/ - -void ocp_nlp_alias_memory_to_submodules(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, - ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work); -// -void ocp_nlp_initialize_submodules(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, - ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work); -// -void ocp_nlp_approximate_qp_matrices(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, - ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work); -// -void ocp_nlp_approximate_qp_vectors_sqp(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, - ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work); -// -void ocp_nlp_embed_initial_value(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, - ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work); -// -void ocp_nlp_update_variables_sqp(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, - ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work, double alpha); -// -int ocp_nlp_precompute_common(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, - ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work); -// -double ocp_nlp_line_search(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, - ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work, - int check_early_termination); -// -double ocp_nlp_evaluate_merit_fun(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, - ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work); -// -void ocp_nlp_initialize_t_slacks(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, - ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work); -// -void ocp_nlp_res_compute(ocp_nlp_dims *dims, ocp_nlp_in *in, ocp_nlp_out *out, - ocp_nlp_res *res, ocp_nlp_memory *mem); -// -void ocp_nlp_cost_compute(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, - ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_COMMON_H_ -/// @} -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_bgh.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_bgh.h deleted file mode 100644 index 9dbf16f6dc..0000000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_bgh.h +++ /dev/null @@ -1,238 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \addtogroup ocp_nlp -/// @{ -/// \addtogroup ocp_nlp_constraints -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_CONSTRAINTS_BGH_H_ -#define ACADOS_OCP_NLP_OCP_NLP_CONSTRAINTS_BGH_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// acados -#include "acados/ocp_qp/ocp_qp_common.h" -#include "acados/ocp_nlp/ocp_nlp_constraints_common.h" -#include "acados/utils/external_function_generic.h" -#include "acados/utils/types.h" - - - -/************************************************ - * dims - ************************************************/ - -typedef struct -{ - int nx; - int nu; - int nz; - int nb; // nbx + nbu - int nbu; // number of input box constraints - int nbx; // number of state box constraints - int ng; // number of general linear constraints - int nh; // number of nonlinear path constraints - int ns; // nsbu + nsbx + nsg + nsh - int nsbu; // number of softened input bounds - int nsbx; // number of softened state bounds - int nsg; // number of softened general linear constraints - int nsh; // number of softened nonlinear constraints - int nbue; // number of input box constraints which are equality - int nbxe; // number of state box constraints which are equality - int nge; // number of general linear constraints which are equality - int nhe; // number of nonlinear path constraints which are equality -} ocp_nlp_constraints_bgh_dims; - -// -acados_size_t ocp_nlp_constraints_bgh_dims_calculate_size(void *config); -// -void *ocp_nlp_constraints_bgh_dims_assign(void *config, void *raw_memory); -// -void ocp_nlp_constraints_bgh_dims_get(void *config_, void *dims_, const char *field, int* value); -// -void ocp_nlp_constraints_bgh_dims_set(void *config_, void *dims_, - const char *field, const int* value); - - -/************************************************ - * model - ************************************************/ - -typedef struct -{ - int *idxb; - int *idxs; - int *idxe; - struct blasfeo_dvec d; // gathers bounds - struct blasfeo_dmat DCt; // general linear constraint matrix - // lg <= [D, C] * [u; x] <= ug - external_function_generic *nl_constr_h_fun; // nonlinear: lh <= h(x,u) <= uh - external_function_generic *nl_constr_h_fun_jac; // nonlinear: lh <= h(x,u) <= uh - external_function_generic *nl_constr_h_fun_jac_hess; // nonlinear: lh <= h(x,u) <= uh -} ocp_nlp_constraints_bgh_model; - -// -acados_size_t ocp_nlp_constraints_bgh_model_calculate_size(void *config, void *dims); -// -void *ocp_nlp_constraints_bgh_model_assign(void *config, void *dims, void *raw_memory); -// -int ocp_nlp_constraints_bgh_model_set(void *config_, void *dims_, - void *model_, const char *field, void *value); - -// -void ocp_nlp_constraints_bgh_model_get(void *config_, void *dims_, - void *model_, const char *field, void *value); - - -/************************************************ - * options - ************************************************/ - -typedef struct -{ - int compute_adj; - int compute_hess; -} ocp_nlp_constraints_bgh_opts; - -// -acados_size_t ocp_nlp_constraints_bgh_opts_calculate_size(void *config, void *dims); -// -void *ocp_nlp_constraints_bgh_opts_assign(void *config, void *dims, void *raw_memory); -// -void ocp_nlp_constraints_bgh_opts_initialize_default(void *config, void *dims, void *opts); -// -void ocp_nlp_constraints_bgh_opts_update(void *config, void *dims, void *opts); -// -void ocp_nlp_constraints_bgh_opts_set(void *config, void *opts, char *field, void *value); - - - -/************************************************ - * memory - ************************************************/ - -typedef struct -{ - struct blasfeo_dvec fun; - struct blasfeo_dvec adj; - struct blasfeo_dvec *ux; // pointer to ux in nlp_out - struct blasfeo_dvec *tmp_ux; // pointer to ux in tmp_nlp_out - struct blasfeo_dvec *lam; // pointer to lam in nlp_out - struct blasfeo_dvec *tmp_lam;// pointer to lam in tmp_nlp_out - struct blasfeo_dvec *z_alg; // pointer to z_alg in ocp_nlp memory - struct blasfeo_dmat *DCt; // pointer to DCt in qp_in - struct blasfeo_dmat *RSQrq; // pointer to RSQrq in qp_in - struct blasfeo_dmat *dzduxt; // pointer to dzduxt in ocp_nlp memory - int *idxb; // pointer to idxb[ii] in qp_in - int *idxs_rev; // pointer to idxs_rev[ii] in qp_in - int *idxe; // pointer to idxe[ii] in qp_in -} ocp_nlp_constraints_bgh_memory; - -// -acados_size_t ocp_nlp_constraints_bgh_memory_calculate_size(void *config, void *dims, void *opts); -// -void *ocp_nlp_constraints_bgh_memory_assign(void *config, void *dims, void *opts, void *raw_memory); -// -struct blasfeo_dvec *ocp_nlp_constraints_bgh_memory_get_fun_ptr(void *memory_); -// -struct blasfeo_dvec *ocp_nlp_constraints_bgh_memory_get_adj_ptr(void *memory_); -// -void ocp_nlp_constraints_bgh_memory_set_ux_ptr(struct blasfeo_dvec *ux, void *memory_); -// -void ocp_nlp_constraints_bgh_memory_set_tmp_ux_ptr(struct blasfeo_dvec *tmp_ux, void *memory_); -// -void ocp_nlp_constraints_bgh_memory_set_lam_ptr(struct blasfeo_dvec *lam, void *memory_); -// -void ocp_nlp_constraints_bgh_memory_set_tmp_lam_ptr(struct blasfeo_dvec *tmp_lam, void *memory_); -// -void ocp_nlp_constraints_bgh_memory_set_DCt_ptr(struct blasfeo_dmat *DCt, void *memory); -// -void ocp_nlp_constraints_bgh_memory_set_RSQrq_ptr(struct blasfeo_dmat *RSQrq, void *memory_); -// -void ocp_nlp_constraints_bgh_memory_set_z_alg_ptr(struct blasfeo_dvec *z_alg, void *memory_); -// -void ocp_nlp_constraints_bgh_memory_set_dzduxt_ptr(struct blasfeo_dmat *dzduxt, void *memory_); -// -void ocp_nlp_constraints_bgh_memory_set_idxb_ptr(int *idxb, void *memory_); -// -void ocp_nlp_constraints_bgh_memory_set_idxs_rev_ptr(int *idxs_rev, void *memory_); -// -void ocp_nlp_constraints_bgh_memory_set_idxe_ptr(int *idxe, void *memory_); - - - -/************************************************ - * workspace - ************************************************/ - -typedef struct -{ - struct blasfeo_dmat tmp_nv_nv; - struct blasfeo_dmat tmp_nz_nh; - struct blasfeo_dmat tmp_nv_nh; - struct blasfeo_dmat tmp_nz_nv; - struct blasfeo_dmat hess_z; - struct blasfeo_dvec tmp_ni; - struct blasfeo_dvec tmp_nh; -} ocp_nlp_constraints_bgh_workspace; - -// -acados_size_t ocp_nlp_constraints_bgh_workspace_calculate_size(void *config, void *dims, void *opts); - -/* functions */ - -// -void ocp_nlp_constraints_bgh_config_initialize_default(void *config); -// -void ocp_nlp_constraints_bgh_initialize(void *config, void *dims, void *model, void *opts, - void *mem, void *work); -// -void ocp_nlp_constraints_bgh_update_qp_matrices(void *config_, void *dims, void *model_, - void *opts_, void *memory_, void *work_); - -// -void ocp_nlp_constraints_bgh_compute_fun(void *config_, void *dims, void *model_, - void *opts_, void *memory_, void *work_); -// -void ocp_nlp_constraints_bgh_bounds_update(void *config_, void *dims, void *model_, - void *opts_, void *memory_, void *work_); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_CONSTRAINTS_BGH_H_ -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_bgp.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_bgp.h deleted file mode 100644 index eb05edf7a6..0000000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_bgp.h +++ /dev/null @@ -1,218 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \addtogroup ocp_nlp -/// @{ -/// \addtogroup ocp_nlp_constraints -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_CONSTRAINTS_BGP_H_ -#define ACADOS_OCP_NLP_OCP_NLP_CONSTRAINTS_BGP_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// acados -#include "acados/ocp_qp/ocp_qp_common.h" -#include "acados/ocp_nlp/ocp_nlp_constraints_common.h" -#include "acados/utils/external_function_generic.h" -#include "acados/utils/types.h" - - - -/* dims */ - -typedef struct -{ - int nx; - int nu; - int nz; - int nb; // nbx + nbu - int nbu; - int nbx; - int ng; // number of general linear constraints - int nphi; // dimension of convex outer part - int ns; // nsbu + nsbx + nsg + nsphi - int nsbu; // number of softened input bounds - int nsbx; // number of softened state bounds - int nsg; // number of softened general linear constraints - int nsphi; // number of softened nonlinear constraints - int nr; // dimension of nonlinear function in convex_over_nonlinear constraint - int nbue; // number of input box constraints which are equality - int nbxe; // number of state box constraints which are equality - int nge; // number of general linear constraints which are equality - int nphie; // number of nonlinear path constraints which are equality -} ocp_nlp_constraints_bgp_dims; - -// -acados_size_t ocp_nlp_constraints_bgp_dims_calculate_size(void *config); -// -void *ocp_nlp_constraints_bgp_dims_assign(void *config, void *raw_memory); -// -void ocp_nlp_constraints_bgp_dims_get(void *config_, void *dims_, const char *field, int* value); - - -/* model */ - -typedef struct -{ - // ocp_nlp_constraints_bgp_dims *dims; - int *idxb; - int *idxs; - int *idxe; - struct blasfeo_dvec d; - struct blasfeo_dmat DCt; - external_function_generic *nl_constr_phi_o_r_fun_phi_jac_ux_z_phi_hess_r_jac_ux; - external_function_generic *nl_constr_phi_o_r_fun; - external_function_generic *nl_constr_r_fun_jac; -} ocp_nlp_constraints_bgp_model; - -// -acados_size_t ocp_nlp_constraints_bgp_calculate_size(void *config, void *dims); -// -void *ocp_nlp_constraints_bgp_assign(void *config, void *dims, void *raw_memory); -// -int ocp_nlp_constraints_bgp_model_set(void *config_, void *dims_, - void *model_, const char *field, void *value); -// -void ocp_nlp_constraints_bgp_model_get(void *config_, void *dims_, - void *model_, const char *field, void *value); - -/* options */ - -typedef struct -{ - int compute_adj; - int compute_hess; -} ocp_nlp_constraints_bgp_opts; - -// -acados_size_t ocp_nlp_constraints_bgp_opts_calculate_size(void *config, void *dims); -// -void *ocp_nlp_constraints_bgp_opts_assign(void *config, void *dims, void *raw_memory); -// -void ocp_nlp_constraints_bgp_opts_initialize_default(void *config, void *dims, void *opts); -// -void ocp_nlp_constraints_bgp_opts_update(void *config, void *dims, void *opts); -// -void ocp_nlp_constraints_bgp_opts_set(void *config, void *opts, char *field, void *value); - -/* memory */ - -typedef struct -{ - struct blasfeo_dvec fun; - struct blasfeo_dvec adj; - struct blasfeo_dvec *ux; // pointer to ux in nlp_out - struct blasfeo_dvec *tmp_ux; // pointer to ux in tmp_nlp_out - struct blasfeo_dvec *lam; // pointer to lam in nlp_out - struct blasfeo_dvec *tmp_lam;// pointer to lam in tmp_nlp_out - struct blasfeo_dvec *z_alg; // pointer to z_alg in ocp_nlp memory - struct blasfeo_dmat *DCt; // pointer to DCt in qp_in - struct blasfeo_dmat *RSQrq; // pointer to RSQrq in qp_in - struct blasfeo_dmat *dzduxt; // pointer to dzduxt in ocp_nlp memory - int *idxb; // pointer to idxb[ii] in qp_in - int *idxs_rev; // pointer to idxs_rev[ii] in qp_in - int *idxe; // pointer to idxe[ii] in qp_in -} ocp_nlp_constraints_bgp_memory; - -// -acados_size_t ocp_nlp_constraints_bgp_memory_calculate_size(void *config, void *dims, void *opts); -// -void *ocp_nlp_constraints_bgp_memory_assign(void *config, void *dims, void *opts, - void *raw_memory); -// -struct blasfeo_dvec *ocp_nlp_constraints_bgp_memory_get_fun_ptr(void *memory_); -// -struct blasfeo_dvec *ocp_nlp_constraints_bgp_memory_get_adj_ptr(void *memory_); -// -void ocp_nlp_constraints_bgp_memory_set_ux_ptr(struct blasfeo_dvec *ux, void *memory_); -// -void ocp_nlp_constraints_bgp_memory_set_tmp_ux_ptr(struct blasfeo_dvec *tmp_ux, void *memory_); -// -void ocp_nlp_constraints_bgp_memory_set_lam_ptr(struct blasfeo_dvec *lam, void *memory_); -// -void ocp_nlp_constraints_bgp_memory_set_tmp_lam_ptr(struct blasfeo_dvec *tmp_lam, void *memory_); -// -void ocp_nlp_constraints_bgp_memory_set_DCt_ptr(struct blasfeo_dmat *DCt, void *memory); -// -void ocp_nlp_constraints_bgp_memory_set_z_alg_ptr(struct blasfeo_dvec *z_alg, void *memory_); -// -void ocp_nlp_constraints_bgp_memory_set_dzduxt_ptr(struct blasfeo_dmat *dzduxt, void *memory_); -// -void ocp_nlp_constraints_bgp_memory_set_idxb_ptr(int *idxb, void *memory_); -// -void ocp_nlp_constraints_bgp_memory_set_idxs_rev_ptr(int *idxs_rev, void *memory_); -// -void ocp_nlp_constraints_bgh_memory_set_idxe_ptr(int *idxe, void *memory_); - -/* workspace */ - -typedef struct -{ - struct blasfeo_dvec tmp_ni; - struct blasfeo_dmat jac_r_ux_tran; - struct blasfeo_dmat tmp_nr_nphi_nr; - struct blasfeo_dmat tmp_nv_nr; - struct blasfeo_dmat tmp_nv_nphi; - struct blasfeo_dmat tmp_nz_nphi; -} ocp_nlp_constraints_bgp_workspace; - -// -acados_size_t ocp_nlp_constraints_bgp_workspace_calculate_size(void *config, void *dims, void *opts); - -/* functions */ - -// -void ocp_nlp_constraints_bgp_config_initialize_default(void *config); -// -void ocp_nlp_constraints_bgp_initialize(void *config, void *dims, void *model, - void *opts, void *mem, void *work); -// -void ocp_nlp_constraints_bgp_update_qp_matrices(void *config_, void *dims, - void *model_, void *opts_, void *memory_, void *work_); -// -void ocp_nlp_constraints_bgp_compute_fun(void *config_, void *dims, - void *model_, void *opts_, void *memory_, void *work_); -// -void ocp_nlp_constraints_bgp_bounds_update(void *config_, void *dims, void *model_, - void *opts_, void *memory_, void *work_); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_CONSTRAINTS_BGP_H_ -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_common.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_common.h deleted file mode 100644 index bb73c468de..0000000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_common.h +++ /dev/null @@ -1,108 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \ingroup ocp_nlp -/// @{ - -/// \defgroup ocp_nlp_constraints ocp_nlp_constraints -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_CONSTRAINTS_COMMON_H_ -#define ACADOS_OCP_NLP_OCP_NLP_CONSTRAINTS_COMMON_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// acados -#include "acados/ocp_qp/ocp_qp_common.h" -#include "acados/utils/external_function_generic.h" -#include "acados/utils/types.h" - - - -/************************************************ - * config - ************************************************/ - -typedef struct -{ - acados_size_t (*dims_calculate_size)(void *config); - void *(*dims_assign)(void *config, void *raw_memory); - acados_size_t (*model_calculate_size)(void *config, void *dims); - void *(*model_assign)(void *config, void *dims, void *raw_memory); - int (*model_set)(void *config_, void *dims_, void *model_, const char *field, void *value); - void (*model_get)(void *config_, void *dims_, void *model_, const char *field, void *value); - acados_size_t (*opts_calculate_size)(void *config, void *dims); - void *(*opts_assign)(void *config, void *dims, void *raw_memory); - void (*opts_initialize_default)(void *config, void *dims, void *opts); - void (*opts_update)(void *config, void *dims, void *opts); - void (*opts_set)(void *config, void *opts, char *field, void *value); - acados_size_t (*memory_calculate_size)(void *config, void *dims, void *opts); - struct blasfeo_dvec *(*memory_get_fun_ptr)(void *memory); - struct blasfeo_dvec *(*memory_get_adj_ptr)(void *memory); - void (*memory_set_ux_ptr)(struct blasfeo_dvec *ux, void *memory); - void (*memory_set_tmp_ux_ptr)(struct blasfeo_dvec *tmp_ux, void *memory); - void (*memory_set_lam_ptr)(struct blasfeo_dvec *lam, void *memory); - void (*memory_set_tmp_lam_ptr)(struct blasfeo_dvec *tmp_lam, void *memory); - void (*memory_set_DCt_ptr)(struct blasfeo_dmat *DCt, void *memory); - void (*memory_set_RSQrq_ptr)(struct blasfeo_dmat *RSQrq, void *memory); - void (*memory_set_z_alg_ptr)(struct blasfeo_dvec *z_alg, void *memory); - void (*memory_set_dzdux_tran_ptr)(struct blasfeo_dmat *dzduxt, void *memory); - void (*memory_set_idxb_ptr)(int *idxb, void *memory); - void (*memory_set_idxs_rev_ptr)(int *idxs_rev, void *memory); - void (*memory_set_idxe_ptr)(int *idxe, void *memory); - void *(*memory_assign)(void *config, void *dims, void *opts, void *raw_memory); - acados_size_t (*workspace_calculate_size)(void *config, void *dims, void *opts); - void (*initialize)(void *config, void *dims, void *model, void *opts, void *mem, void *work); - void (*update_qp_matrices)(void *config, void *dims, void *model, void *opts, void *mem, void *work); - void (*compute_fun)(void *config, void *dims, void *model, void *opts, void *mem, void *work); - void (*bounds_update)(void *config, void *dims, void *model, void *opts, void *mem, void *work); - void (*config_initialize_default)(void *config); - // dimension setters - void (*dims_set)(void *config_, void *dims_, const char *field, const int *value); - void (*dims_get)(void *config_, void *dims_, const char *field, int* value); -} ocp_nlp_constraints_config; - -// -acados_size_t ocp_nlp_constraints_config_calculate_size(); -// -ocp_nlp_constraints_config *ocp_nlp_constraints_config_assign(void *raw_memory); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_CONSTRAINTS_COMMON_H_ -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_common.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_common.h deleted file mode 100644 index eb40564036..0000000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_common.h +++ /dev/null @@ -1,107 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// -/// \defgroup ocp_nlp_cost ocp_nlp_cost -/// - -/// \addtogroup ocp_nlp_cost ocp_nlp_cost -/// @{ -/// \addtogroup ocp_nlp_cost_common ocp_nlp_cost_common -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_COST_COMMON_H_ -#define ACADOS_OCP_NLP_OCP_NLP_COST_COMMON_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// acados -#include "acados/utils/external_function_generic.h" -#include "acados/utils/types.h" - - - -/************************************************ - * config - ************************************************/ - -typedef struct -{ - acados_size_t (*dims_calculate_size)(void *config); - void *(*dims_assign)(void *config, void *raw_memory); - void (*dims_set)(void *config_, void *dims_, const char *field, int *value); - void (*dims_get)(void *config_, void *dims_, const char *field, int *value); - acados_size_t (*model_calculate_size)(void *config, void *dims); - void *(*model_assign)(void *config, void *dims, void *raw_memory); - int (*model_set)(void *config_, void *dims_, void *model_, const char *field, void *value_); - acados_size_t (*opts_calculate_size)(void *config, void *dims); - void *(*opts_assign)(void *config, void *dims, void *raw_memory); - void (*opts_initialize_default)(void *config, void *dims, void *opts); - void (*opts_update)(void *config, void *dims, void *opts); - void (*opts_set)(void *config, void *opts, const char *field, void *value); - acados_size_t (*memory_calculate_size)(void *config, void *dims, void *opts); - double *(*memory_get_fun_ptr)(void *memory); - struct blasfeo_dvec *(*memory_get_grad_ptr)(void *memory); - void (*memory_set_ux_ptr)(struct blasfeo_dvec *ux, void *memory); - void (*memory_set_tmp_ux_ptr)(struct blasfeo_dvec *tmp_ux, void *memory); - void (*memory_set_z_alg_ptr)(struct blasfeo_dvec *z_alg, void *memory); - void (*memory_set_dzdux_tran_ptr)(struct blasfeo_dmat *dzdux, void *memory); - void (*memory_set_RSQrq_ptr)(struct blasfeo_dmat *RSQrq, void *memory); - void (*memory_set_Z_ptr)(struct blasfeo_dvec *Z, void *memory); - void *(*memory_assign)(void *config, void *dims, void *opts, void *raw_memory); - acados_size_t (*workspace_calculate_size)(void *config, void *dims, void *opts); - void (*initialize)(void *config_, void *dims, void *model_, void *opts_, void *mem_, void *work_); - - // computes the function value, gradient and hessian (approximation) of the cost function - void (*update_qp_matrices)(void *config_, void *dims, void *model_, void *opts_, void *mem_, void *work_); - // computes the cost function value (intended for globalization) - void (*compute_fun)(void *config_, void *dims, void *model_, void *opts_, void *mem_, void *work_); - void (*config_initialize_default)(void *config); - void (*precompute)(void *config_, void *dims_, void *model_, void *opts_, void *memory_, void *work_); - -} ocp_nlp_cost_config; - -// -acados_size_t ocp_nlp_cost_config_calculate_size(); -// -ocp_nlp_cost_config *ocp_nlp_cost_config_assign(void *raw_memory); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_COST_COMMON_H_ -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_conl.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_conl.h deleted file mode 100644 index 2eb3f5d127..0000000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_conl.h +++ /dev/null @@ -1,207 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \addtogroup ocp_nlp -/// @{ -/// \addtogroup ocp_nlp_cost ocp_nlp_cost -/// @{ -/// \addtogroup ocp_nlp_cost_conl ocp_nlp_cost_conl -/// \brief This module implements convex-over-nonlinear costs of the form -/// \f$\min_{x,u,z} \psi(y(x,u,z,p) - y_{\text{ref}}, p)\f$, - - -#ifndef ACADOS_OCP_NLP_OCP_NLP_COST_CONL_H_ -#define ACADOS_OCP_NLP_OCP_NLP_COST_CONL_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// blasfeo -#include "blasfeo/include/blasfeo_common.h" - -// acados -#include "acados/ocp_nlp/ocp_nlp_cost_common.h" -#include "acados/utils/external_function_generic.h" -#include "acados/utils/types.h" - - - -/************************************************ - * dims - ************************************************/ - -typedef struct -{ - int nx; // number of states - int nz; // number of algebraic variables - int nu; // number of inputs - int ny; // number of outputs - int ns; // number of slacks -} ocp_nlp_cost_conl_dims; - -// -acados_size_t ocp_nlp_cost_conl_dims_calculate_size(void *config); -// -void *ocp_nlp_cost_conl_dims_assign(void *config, void *raw_memory); -// -void ocp_nlp_cost_conl_dims_initialize(void *config, void *dims, int nx, int nu, int ny, int ns, int nz); -// -void ocp_nlp_cost_conl_dims_set(void *config_, void *dims_, const char *field, int* value); -// -void ocp_nlp_cost_conl_dims_get(void *config_, void *dims_, const char *field, int* value); - - - -/************************************************ - * model - ************************************************/ - -typedef struct -{ - // slack penalty has the form z^T * s + .5 * s^T * Z * s - external_function_generic *conl_cost_fun; - external_function_generic *conl_cost_fun_jac_hess; - struct blasfeo_dvec y_ref; - struct blasfeo_dvec Z; // diagonal Hessian of slacks as vector - struct blasfeo_dvec z; // gradient of slacks as vector - double scaling; -} ocp_nlp_cost_conl_model; - -// -acados_size_t ocp_nlp_cost_conl_model_calculate_size(void *config, void *dims); -// -void *ocp_nlp_cost_conl_model_assign(void *config, void *dims, void *raw_memory); -// -int ocp_nlp_cost_conl_model_set(void *config_, void *dims_, void *model_, const char *field, void *value_); - - - -/************************************************ - * options - ************************************************/ - -typedef struct -{ - bool gauss_newton_hess; // dummy options, we always use a gauss-newton hessian -} ocp_nlp_cost_conl_opts; - -// -acados_size_t ocp_nlp_cost_conl_opts_calculate_size(void *config, void *dims); -// -void *ocp_nlp_cost_conl_opts_assign(void *config, void *dims, void *raw_memory); -// -void ocp_nlp_cost_conl_opts_initialize_default(void *config, void *dims, void *opts); -// -void ocp_nlp_cost_conl_opts_update(void *config, void *dims, void *opts); -// -void ocp_nlp_cost_conl_opts_set(void *config, void *opts, const char *field, void *value); - - - -/************************************************ - * memory - ************************************************/ -typedef struct -{ - struct blasfeo_dvec grad; // gradient of cost function - struct blasfeo_dvec *ux; // pointer to ux in nlp_out - struct blasfeo_dvec *tmp_ux; // pointer to ux in tmp_nlp_out - struct blasfeo_dmat *RSQrq; // pointer to RSQrq in qp_in - struct blasfeo_dvec *Z; // pointer to Z in qp_in - struct blasfeo_dvec *z_alg; ///< pointer to z in sim_out - struct blasfeo_dmat *dzdux_tran; ///< pointer to sensitivity of a wrt ux in sim_out - double fun; ///< value of the cost function -} ocp_nlp_cost_conl_memory; - -// -acados_size_t ocp_nlp_cost_conl_memory_calculate_size(void *config, void *dims, void *opts); -// -void *ocp_nlp_cost_conl_memory_assign(void *config, void *dims, void *opts, void *raw_memory); -// -double *ocp_nlp_cost_conl_memory_get_fun_ptr(void *memory_); -// -struct blasfeo_dvec *ocp_nlp_cost_conl_memory_get_grad_ptr(void *memory_); -// -void ocp_nlp_cost_conl_memory_set_RSQrq_ptr(struct blasfeo_dmat *RSQrq, void *memory); -// -void ocp_nlp_cost_conl_memory_set_Z_ptr(struct blasfeo_dvec *Z, void *memory); -// -void ocp_nlp_cost_conl_memory_set_ux_ptr(struct blasfeo_dvec *ux, void *memory_); -// -void ocp_nlp_cost_conl_memory_set_tmp_ux_ptr(struct blasfeo_dvec *tmp_ux, void *memory_); -// -void ocp_nlp_cost_conl_memory_set_z_alg_ptr(struct blasfeo_dvec *z_alg, void *memory_); -// -void ocp_nlp_cost_conl_memory_set_dzdux_tran_ptr(struct blasfeo_dmat *dzdux_tran, void *memory_); - -/************************************************ - * workspace - ************************************************/ - -typedef struct -{ - struct blasfeo_dmat W; // hessian of outer loss function - struct blasfeo_dmat W_chol; // cholesky factor of hessian of outer loss function - struct blasfeo_dmat Jt_ux; // jacobian of inner residual function - struct blasfeo_dmat Jt_ux_tilde; // jacobian of inner residual function plus gradient contribution of algebraic variables - struct blasfeo_dmat Jt_z; // jacobian of inner residual function wrt algebraic variables - struct blasfeo_dmat tmp_nv_ny; - struct blasfeo_dvec tmp_ny; - struct blasfeo_dvec tmp_2ns; -} ocp_nlp_cost_conl_workspace; - -// -acados_size_t ocp_nlp_cost_conl_workspace_calculate_size(void *config, void *dims, void *opts); - -/************************************************ - * functions - ************************************************/ - -// -void ocp_nlp_cost_conl_precompute(void *config_, void *dims_, void *model_, void *opts_, void *memory_, void *work_); -// -void ocp_nlp_cost_conl_config_initialize_default(void *config); -// -void ocp_nlp_cost_conl_initialize(void *config_, void *dims, void *model_, void *opts_, void *mem_, void *work_); -// -void ocp_nlp_cost_conl_update_qp_matrices(void *config_, void *dims, void *model_, void *opts_, void *memory_, void *work_); -// -void ocp_nlp_cost_conl_compute_fun(void *config_, void *dims, void *model_, void *opts_, void *memory_, void *work_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_COST_CONL_H_ -/// @} -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_external.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_external.h deleted file mode 100644 index 78958270de..0000000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_external.h +++ /dev/null @@ -1,187 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_OCP_NLP_OCP_NLP_COST_EXTERNAL_H_ -#define ACADOS_OCP_NLP_OCP_NLP_COST_EXTERNAL_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// blasfeo -#include "blasfeo/include/blasfeo_common.h" - -// acados -#include "acados/ocp_nlp/ocp_nlp_cost_common.h" -#include "acados/utils/external_function_generic.h" -#include "acados/utils/types.h" - -/************************************************ - * dims - ************************************************/ - -typedef struct -{ - int nx; // number of states - int nz; // number of algebraic variables - int nu; // number of inputs - int ns; // number of slacks -} ocp_nlp_cost_external_dims; - -// -acados_size_t ocp_nlp_cost_external_dims_calculate_size(void *config); -// -void *ocp_nlp_cost_external_dims_assign(void *config, void *raw_memory); -// -void ocp_nlp_cost_external_dims_set(void *config_, void *dims_, const char *field, int* value); -// -void ocp_nlp_cost_external_dims_get(void *config_, void *dims_, const char *field, int* value); - -/************************************************ - * model - ************************************************/ - -typedef struct -{ - external_function_generic *ext_cost_fun; // function - external_function_generic *ext_cost_fun_jac_hess; // function, gradient and hessian - external_function_generic *ext_cost_fun_jac; // function, gradient - struct blasfeo_dvec Z; - struct blasfeo_dvec z; - struct blasfeo_dmat numerical_hessian; // custom hessian approximation - double scaling; -} ocp_nlp_cost_external_model; - -// -acados_size_t ocp_nlp_cost_external_model_calculate_size(void *config, void *dims); -// -void *ocp_nlp_cost_external_model_assign(void *config, void *dims, void *raw_memory); - - - -/************************************************ - * options - ************************************************/ - -typedef struct -{ - int use_numerical_hessian; // > 0 indicating custom hessian is used instead of CasADi evaluation -} ocp_nlp_cost_external_opts; - -// -acados_size_t ocp_nlp_cost_external_opts_calculate_size(void *config, void *dims); -// -void *ocp_nlp_cost_external_opts_assign(void *config, void *dims, void *raw_memory); -// -void ocp_nlp_cost_external_opts_initialize_default(void *config, void *dims, void *opts); -// -void ocp_nlp_cost_external_opts_update(void *config, void *dims, void *opts); -// -void ocp_nlp_cost_external_opts_set(void *config, void *opts, const char *field, void *value); - - - -/************************************************ - * memory - ************************************************/ - -typedef struct -{ - struct blasfeo_dvec grad; // gradient of cost function - struct blasfeo_dvec *ux; // pointer to ux in nlp_out - struct blasfeo_dvec *tmp_ux; // pointer to tmp_ux in nlp_out - struct blasfeo_dmat *RSQrq; // pointer to RSQrq in qp_in - struct blasfeo_dvec *Z; // pointer to Z in qp_in - struct blasfeo_dvec *z_alg; ///< pointer to z in sim_out - struct blasfeo_dmat *dzdux_tran; ///< pointer to sensitivity of a wrt ux in sim_out - double fun; ///< value of the cost function -} ocp_nlp_cost_external_memory; - -// -acados_size_t ocp_nlp_cost_external_memory_calculate_size(void *config, void *dims, void *opts); -// -void *ocp_nlp_cost_external_memory_assign(void *config, void *dims, void *opts, void *raw_memory); -// -double *ocp_nlp_cost_external_memory_get_fun_ptr(void *memory_); -// -struct blasfeo_dvec *ocp_nlp_cost_external_memory_get_grad_ptr(void *memory_); -// -void ocp_nlp_cost_external_memory_set_RSQrq_ptr(struct blasfeo_dmat *RSQrq, void *memory); -// -void ocp_nlp_cost_ls_memory_set_Z_ptr(struct blasfeo_dvec *Z, void *memory); -// -void ocp_nlp_cost_external_memory_set_ux_ptr(struct blasfeo_dvec *ux, void *memory_); -// -void ocp_nlp_cost_external_memory_set_tmp_ux_ptr(struct blasfeo_dvec *tmp_ux, void *memory_); -// -void ocp_nlp_cost_external_memory_set_z_alg_ptr(struct blasfeo_dvec *z_alg, void *memory_); -// -void ocp_nlp_cost_external_memory_set_dzdux_tran_ptr(struct blasfeo_dmat *dzdux_tran, void *memory_); - -/************************************************ - * workspace - ************************************************/ - -typedef struct -{ - struct blasfeo_dmat tmp_nunx_nunx; - struct blasfeo_dmat tmp_nz_nz; - struct blasfeo_dmat tmp_nz_nunx; - struct blasfeo_dvec tmp_nunxnz; - struct blasfeo_dvec tmp_2ns; // temporary vector of dimension 2*ns -} ocp_nlp_cost_external_workspace; - -// -acados_size_t ocp_nlp_cost_external_workspace_calculate_size(void *config, void *dims, void *opts); - -/************************************************ - * functions - ************************************************/ - -// -void ocp_nlp_cost_external_precompute(void *config_, void *dims_, void *model_, void *opts_, void *memory_, void *work_); -// -void ocp_nlp_cost_external_config_initialize_default(void *config); -// -void ocp_nlp_cost_external_initialize(void *config_, void *dims, void *model_, - void *opts_, void *mem_, void *work_); -// -void ocp_nlp_cost_external_update_qp_matrices(void *config_, void *dims, void *model_, - void *opts_, void *memory_, void *work_); -// -void ocp_nlp_cost_external_compute_fun(void *config_, void *dims, void *model_, - void *opts_, void *memory_, void *work_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_COST_EXTERNAL_H_ diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_ls.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_ls.h deleted file mode 100644 index 801e9a5b87..0000000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_ls.h +++ /dev/null @@ -1,243 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \addtogroup ocp_nlp -/// @{ -/// \addtogroup ocp_nlp_cost ocp_nlp_cost -/// @{ -/// \addtogroup ocp_nlp_cost_ls ocp_nlp_cost_ls -/// \brief This module implements linear-least squares costs of the form -/// \f$\min_{x,u,z} \| V_x x + V_u u + V_z z - y_{\text{ref}}\|_W^2\f$. -/// @{ - - - -#ifndef ACADOS_OCP_NLP_OCP_NLP_COST_LS_H_ -#define ACADOS_OCP_NLP_OCP_NLP_COST_LS_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// blasfeo -#include "blasfeo/include/blasfeo_common.h" - -// acados -#include "acados/ocp_nlp/ocp_nlp_cost_common.h" -#include "acados/utils/external_function_generic.h" -#include "acados/utils/types.h" - - -//////////////////////////////////////////////////////////////////////////////// -// dims // -//////////////////////////////////////////////////////////////////////////////// - -typedef struct -{ - int nx; // number of states - int nz; // number of algebraic variables - int nu; // number of inputs - int ny; // number of outputs - int ns; // number of slacks -} ocp_nlp_cost_ls_dims; - - -/// Calculate the size of the ocp_nlp_cost_ls_dims struct -/// -/// \param[in] config_ structure containing configuration of ocp_nlp_cost -/// module -/// \param[out] [] -/// \return \c size of ocp_nlp_dims struct -acados_size_t ocp_nlp_cost_ls_dims_calculate_size(void *config); - - -/// Assign memory pointed to by raw_memory to ocp_nlp-cost_ls dims struct -/// -/// \param[in] config structure containing configuration of ocp_nlp_cost -/// module -/// \param[in] raw_memory pointer to memory location -/// \param[out] [] -/// \return dims -void *ocp_nlp_cost_ls_dims_assign(void *config, void *raw_memory); -// -void ocp_nlp_cost_ls_dims_set(void *config_, void *dims_, const char *field, int* value); -// -void ocp_nlp_cost_ls_dims_get(void *config_, void *dims_, const char *field, int* value); - - -//////////////////////////////////////////////////////////////////////////////// -// model // -//////////////////////////////////////////////////////////////////////////////// - - -/// structure containing the data describing the linear least-square cost -typedef struct -{ - // slack penalty has the form z^T * s + .5 * s^T * Z * s - struct blasfeo_dmat Cyt; ///< output matrix: Cy * [u,x] = y; in transposed form - struct blasfeo_dmat Vz; ///< Vz in ls cost Vx*x + Vu*u + Vz*z - struct blasfeo_dmat W; ///< ls norm corresponding to this matrix - struct blasfeo_dvec y_ref; ///< yref - struct blasfeo_dvec Z; ///< diagonal Hessian of slacks as vector (lower and upper) - struct blasfeo_dvec z; ///< gradient of slacks as vector (lower and upper) - double scaling; - int W_changed; ///< flag indicating whether W has changed and needs to be refactorized - int Cyt_or_scaling_changed; ///< flag indicating whether Cyt or scaling has changed and Hessian needs to be recomputed -} ocp_nlp_cost_ls_model; - -// -acados_size_t ocp_nlp_cost_ls_model_calculate_size(void *config, void *dims); -// -void *ocp_nlp_cost_ls_model_assign(void *config, void *dims, void *raw_memory); -// -int ocp_nlp_cost_ls_model_set(void *config_, void *dims_, void *model_, - const char *field, void *value_); - - - -//////////////////////////////////////////////////////////////////////////////// -// options // -//////////////////////////////////////////////////////////////////////////////// - - - -typedef struct -{ - int dummy; // struct can't be void -} ocp_nlp_cost_ls_opts; - -// -acados_size_t ocp_nlp_cost_ls_opts_calculate_size(void *config, void *dims); -// -void *ocp_nlp_cost_ls_opts_assign(void *config, void *dims, void *raw_memory); -// -void ocp_nlp_cost_ls_opts_initialize_default(void *config, void *dims, void *opts); -// -void ocp_nlp_cost_ls_opts_update(void *config, void *dims, void *opts); -// -void ocp_nlp_cost_ls_opts_set(void *config, void *opts, const char *field, void *value); - - - -//////////////////////////////////////////////////////////////////////////////// -// memory // -//////////////////////////////////////////////////////////////////////////////// - - - -/// structure containing the memory associated with cost_ls component -/// of the ocp_nlp module -typedef struct -{ - struct blasfeo_dmat hess; ///< hessian of cost function - struct blasfeo_dmat W_chol; ///< cholesky factor of weight matrix - struct blasfeo_dvec res; ///< ls residual r(x) - struct blasfeo_dvec grad; ///< gradient of cost function - struct blasfeo_dvec *ux; ///< pointer to ux in nlp_out - struct blasfeo_dvec *tmp_ux; ///< pointer to ux in tmp_nlp_out - struct blasfeo_dvec *z_alg; ///< pointer to z in sim_out - struct blasfeo_dmat *dzdux_tran; ///< pointer to sensitivity of a wrt ux in sim_out - struct blasfeo_dmat *RSQrq; ///< pointer to RSQrq in qp_in - struct blasfeo_dvec *Z; ///< pointer to Z in qp_in - double fun; ///< value of the cost function -} ocp_nlp_cost_ls_memory; - -// -acados_size_t ocp_nlp_cost_ls_memory_calculate_size(void *config, void *dims, void *opts); -// -void *ocp_nlp_cost_ls_memory_assign(void *config, void *dims, void *opts, void *raw_memory); -// -double *ocp_nlp_cost_ls_memory_get_fun_ptr(void *memory_); -// -struct blasfeo_dvec *ocp_nlp_cost_ls_memory_get_grad_ptr(void *memory_); -// -void ocp_nlp_cost_ls_memory_set_RSQrq_ptr(struct blasfeo_dmat *RSQrq, void *memory); -// -void ocp_nlp_cost_ls_memory_set_Z_ptr(struct blasfeo_dvec *Z, void *memory); -// -void ocp_nlp_cost_ls_memory_set_ux_ptr(struct blasfeo_dvec *ux, void *memory_); -// -void ocp_nlp_cost_ls_memory_set_tmp_ux_ptr(struct blasfeo_dvec *tmp_ux, void *memory_); -// -void ocp_nlp_cost_ls_memory_set_z_alg_ptr(struct blasfeo_dvec *z_alg, void *memory_); -// -void ocp_nlp_cost_ls_memory_set_dzdux_tran_ptr(struct blasfeo_dmat *dzdux_tran, void *memory_); - - - -//////////////////////////////////////////////////////////////////////////////// -// workspace // -//////////////////////////////////////////////////////////////////////////////// - - - -typedef struct -{ - struct blasfeo_dmat tmp_nv_ny; // temporary matrix of dimensions nv, ny - struct blasfeo_dmat Cyt_tilde; // updated Cyt (after z elimination) - struct blasfeo_dmat dzdux_tran; // derivatives of z wrt u and x (tran) - struct blasfeo_dvec tmp_ny; // temporary vector of dimension ny - struct blasfeo_dvec tmp_2ns; // temporary vector of dimension ny - struct blasfeo_dvec tmp_nz; // temporary vector of dimension nz - struct blasfeo_dvec y_ref_tilde; // updated y_ref (after z elimination) -} ocp_nlp_cost_ls_workspace; - -// -acados_size_t ocp_nlp_cost_ls_workspace_calculate_size(void *config, void *dims, void *opts); - - - -//////////////////////////////////////////////////////////////////////////////// -// functions // -//////////////////////////////////////////////////////////////////////////////// - - -// computations that are done once when solver is created -void ocp_nlp_cost_ls_precompute(void *config_, void *dims_, void *model_, void *opts_, void *memory_, void *work_); -// -void ocp_nlp_cost_ls_config_initialize_default(void *config); -// -void ocp_nlp_cost_ls_initialize(void *config_, void *dims, void *model_, void *opts_, - void *mem_, void *work_); -// -void ocp_nlp_cost_ls_update_qp_matrices(void *config_, void *dims, void *model_, - void *opts_, void *memory_, void *work_); -// -void ocp_nlp_cost_ls_compute_fun(void *config_, void *dims, void *model_, void *opts_, void *memory_, void *work_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_COST_LS_H_ -/// @} -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_nls.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_nls.h deleted file mode 100644 index 5ec68cf580..0000000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_nls.h +++ /dev/null @@ -1,211 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \addtogroup ocp_nlp -/// @{ -/// \addtogroup ocp_nlp_cost ocp_nlp_cost -/// @{ -/// \addtogroup ocp_nlp_cost_nls ocp_nlp_cost_nls -/// \brief This module implements nonlinear-least squares costs of the form -/// \f$\min_{x,u,z} \| y(x,u,z,p) - y_{\text{ref}} \|_W^2\f$, - -#ifndef ACADOS_OCP_NLP_OCP_NLP_COST_NLS_H_ -#define ACADOS_OCP_NLP_OCP_NLP_COST_NLS_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// blasfeo -#include "blasfeo/include/blasfeo_common.h" - -// acados -#include "acados/ocp_nlp/ocp_nlp_cost_common.h" -#include "acados/utils/external_function_generic.h" -#include "acados/utils/types.h" - - - -/************************************************ - * dims - ************************************************/ - -typedef struct -{ - int nx; // number of states - int nz; // number of algebraic variables - int nu; // number of inputs - int ny; // number of outputs - int ns; // number of slacks -} ocp_nlp_cost_nls_dims; - -// -acados_size_t ocp_nlp_cost_nls_dims_calculate_size(void *config); -// -void *ocp_nlp_cost_nls_dims_assign(void *config, void *raw_memory); -// -void ocp_nlp_cost_nls_dims_set(void *config_, void *dims_, const char *field, int* value); -// -void ocp_nlp_cost_nls_dims_get(void *config_, void *dims_, const char *field, int* value); - - - -/************************************************ - * model - ************************************************/ - -typedef struct -{ - // nonliner function nls_y(x,u) replaces Cy * [x,u] in ls_cost - // slack penalty has the form z^T * s + .5 * s^T * Z * s - external_function_generic *nls_y_fun; // evaluation of nls function - external_function_generic *nls_y_fun_jac; // evaluation nls function and jacobian - external_function_generic *nls_y_hess; // hessian*seeds of nls residuals - struct blasfeo_dmat W; // - struct blasfeo_dvec y_ref; - struct blasfeo_dvec Z; // diagonal Hessian of slacks as vector - struct blasfeo_dvec z; // gradient of slacks as vector - double scaling; - int W_changed; ///< flag indicating whether W has changed and needs to be refactorized -} ocp_nlp_cost_nls_model; - -// -acados_size_t ocp_nlp_cost_nls_model_calculate_size(void *config, void *dims); -// -void *ocp_nlp_cost_nls_model_assign(void *config, void *dims, void *raw_memory); -// -int ocp_nlp_cost_nls_model_set(void *config_, void *dims_, void *model_, const char *field, void *value_); - - - -/************************************************ - * options - ************************************************/ - -typedef struct -{ - bool gauss_newton_hess; // gauss-newton hessian approximation -} ocp_nlp_cost_nls_opts; - -// -acados_size_t ocp_nlp_cost_nls_opts_calculate_size(void *config, void *dims); -// -void *ocp_nlp_cost_nls_opts_assign(void *config, void *dims, void *raw_memory); -// -void ocp_nlp_cost_nls_opts_initialize_default(void *config, void *dims, void *opts); -// -void ocp_nlp_cost_nls_opts_update(void *config, void *dims, void *opts); -// -void ocp_nlp_cost_nls_opts_set(void *config, void *opts, const char *field, void *value); - - - -/************************************************ - * memory - ************************************************/ - -typedef struct -{ - struct blasfeo_dmat W_chol; // cholesky factor of weight matrix - struct blasfeo_dmat Jt; // jacobian of nls fun - struct blasfeo_dvec res; // nls residual r(x) - struct blasfeo_dvec grad; // gradient of cost function - struct blasfeo_dvec *ux; // pointer to ux in nlp_out - struct blasfeo_dvec *tmp_ux; // pointer to ux in tmp_nlp_out - struct blasfeo_dmat *RSQrq; // pointer to RSQrq in qp_in - struct blasfeo_dvec *Z; // pointer to Z in qp_in - struct blasfeo_dvec *z_alg; ///< pointer to z in sim_out - struct blasfeo_dmat *dzdux_tran; ///< pointer to sensitivity of a wrt ux in sim_out - double fun; ///< value of the cost function -} ocp_nlp_cost_nls_memory; - -// -acados_size_t ocp_nlp_cost_nls_memory_calculate_size(void *config, void *dims, void *opts); -// -void *ocp_nlp_cost_nls_memory_assign(void *config, void *dims, void *opts, void *raw_memory); -// -double *ocp_nlp_cost_nls_memory_get_fun_ptr(void *memory_); -// -struct blasfeo_dvec *ocp_nlp_cost_nls_memory_get_grad_ptr(void *memory_); -// -void ocp_nlp_cost_nls_memory_set_RSQrq_ptr(struct blasfeo_dmat *RSQrq, void *memory); -// -void ocp_nlp_cost_nls_memory_set_Z_ptr(struct blasfeo_dvec *Z, void *memory); -// -void ocp_nlp_cost_nls_memory_set_ux_ptr(struct blasfeo_dvec *ux, void *memory_); -// -void ocp_nlp_cost_nls_memory_set_tmp_ux_ptr(struct blasfeo_dvec *tmp_ux, void *memory_); -// -void ocp_nlp_cost_nls_memory_set_z_alg_ptr(struct blasfeo_dvec *z_alg, void *memory_); -// -void ocp_nlp_cost_nls_memory_set_dzdux_tran_ptr(struct blasfeo_dmat *dzdux_tran, void *memory_); - -/************************************************ - * workspace - ************************************************/ - -typedef struct -{ - struct blasfeo_dmat tmp_nv_ny; - struct blasfeo_dmat tmp_nv_nv; - struct blasfeo_dmat Vz; - struct blasfeo_dmat Cyt_tilde; - struct blasfeo_dvec tmp_ny; - struct blasfeo_dvec tmp_2ns; - struct blasfeo_dvec tmp_nz; -} ocp_nlp_cost_nls_workspace; - -// -acados_size_t ocp_nlp_cost_nls_workspace_calculate_size(void *config, void *dims, void *opts); - -/************************************************ - * functions - ************************************************/ - -// -void ocp_nlp_cost_nls_precompute(void *config_, void *dims_, void *model_, void *opts_, void *memory_, void *work_); -// -void ocp_nlp_cost_nls_config_initialize_default(void *config); -// -void ocp_nlp_cost_nls_initialize(void *config_, void *dims, void *model_, void *opts_, void *mem_, void *work_); -// -void ocp_nlp_cost_nls_update_qp_matrices(void *config_, void *dims, void *model_, void *opts_, void *memory_, void *work_); -// -void ocp_nlp_cost_nls_compute_fun(void *config_, void *dims, void *model_, void *opts_, void *memory_, void *work_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_COST_NLS_H_ -/// @} -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_common.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_common.h deleted file mode 100644 index 43fe71b12f..0000000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_common.h +++ /dev/null @@ -1,119 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \ingroup ocp_nlp -/// @{ - -/// \defgroup ocp_nlp_dynamics ocp_nlp_dynamics -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_DYNAMICS_COMMON_H_ -#define ACADOS_OCP_NLP_OCP_NLP_DYNAMICS_COMMON_H_ - -#ifdef __cplusplus -extern "C" { -#endif - - - -// blasfeo -#include "blasfeo/include/blasfeo_common.h" - -// acados -#include "acados/sim/sim_common.h" -#include "acados/utils/external_function_generic.h" -#include "acados/utils/types.h" - - - -/************************************************ - * config - ************************************************/ - -typedef struct -{ - void (*config_initialize_default)(void *config); - sim_config *sim_solver; - /* dims */ - acados_size_t (*dims_calculate_size)(void *config); - void *(*dims_assign)(void *config, void *raw_memory); - void (*dims_set)(void *config_, void *dims_, const char *field, int *value); - void (*dims_get)(void *config_, void *dims_, const char *field, int* value); - /* model */ - acados_size_t (*model_calculate_size)(void *config, void *dims); - void *(*model_assign)(void *config, void *dims, void *raw_memory); - void (*model_set)(void *config_, void *dims_, void *model_, const char *field, void *value_); - /* opts */ - acados_size_t (*opts_calculate_size)(void *config, void *dims); - void *(*opts_assign)(void *config, void *dims, void *raw_memory); - void (*opts_initialize_default)(void *config, void *dims, void *opts); - void (*opts_set)(void *config_, void *opts_, const char *field, void *value); - void (*opts_update)(void *config, void *dims, void *opts); - /* memory */ - acados_size_t (*memory_calculate_size)(void *config, void *dims, void *opts); - void *(*memory_assign)(void *config, void *dims, void *opts, void *raw_memory); - // get shooting node gap x_next(x_n, u_n) - x_{n+1} - struct blasfeo_dvec *(*memory_get_fun_ptr)(void *memory_); - struct blasfeo_dvec *(*memory_get_adj_ptr)(void *memory_); - void (*memory_set_ux_ptr)(struct blasfeo_dvec *ux, void *memory_); - void (*memory_set_tmp_ux_ptr)(struct blasfeo_dvec *tmp_ux, void *memory_); - void (*memory_set_ux1_ptr)(struct blasfeo_dvec *ux1, void *memory_); - void (*memory_set_tmp_ux1_ptr)(struct blasfeo_dvec *tmp_ux1, void *memory_); - void (*memory_set_pi_ptr)(struct blasfeo_dvec *pi, void *memory_); - void (*memory_set_tmp_pi_ptr)(struct blasfeo_dvec *tmp_pi, void *memory_); - void (*memory_set_BAbt_ptr)(struct blasfeo_dmat *BAbt, void *memory_); - void (*memory_set_RSQrq_ptr)(struct blasfeo_dmat *RSQrq, void *memory_); - void (*memory_set_dzduxt_ptr)(struct blasfeo_dmat *mat, void *memory_); - void (*memory_set_sim_guess_ptr)(struct blasfeo_dvec *vec, bool *bool_ptr, void *memory_); - void (*memory_set_z_alg_ptr)(struct blasfeo_dvec *vec, void *memory_); - void (*memory_get)(void *config, void *dims, void *mem, const char *field, void* value); - /* workspace */ - acados_size_t (*workspace_calculate_size)(void *config, void *dims, void *opts); - void (*initialize)(void *config_, void *dims, void *model_, void *opts_, void *mem_, void *work_); - void (*update_qp_matrices)(void *config_, void *dims, void *model_, void *opts_, void *mem_, void *work_); - void (*compute_fun)(void *config_, void *dims, void *model_, void *opts_, void *mem_, void *work_); - int (*precompute)(void *config_, void *dims, void *model_, void *opts_, void *mem_, void *work_); -} ocp_nlp_dynamics_config; - -// -acados_size_t ocp_nlp_dynamics_config_calculate_size(); -// -ocp_nlp_dynamics_config *ocp_nlp_dynamics_config_assign(void *raw_memory); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_DYNAMICS_COMMON_H_ -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_cont.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_cont.h deleted file mode 100644 index 3afdc9f4ed..0000000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_cont.h +++ /dev/null @@ -1,209 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \addtogroup ocp_nlp -/// @{ -/// \addtogroup ocp_nlp_dynamics -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_DYNAMICS_CONT_H_ -#define ACADOS_OCP_NLP_OCP_NLP_DYNAMICS_CONT_H_ - -#ifdef __cplusplus -extern "C" { -#endif - - - -// blasfeo -#include "blasfeo/include/blasfeo_common.h" - -// acados -#include "acados/ocp_nlp/ocp_nlp_dynamics_common.h" -#include "acados/utils/external_function_generic.h" -#include "acados/utils/types.h" -#include "acados_c/sim_interface.h" - - - -/************************************************ - * dims - ************************************************/ - -typedef struct -{ - void *sim; - int nx; // number of states at the current stage - int nz; // number of algebraic states at the current stage - int nu; // number of inputs at the current stage - int nx1; // number of states at the next stage - int nu1; // number of inputes at the next stage -} ocp_nlp_dynamics_cont_dims; - -// -acados_size_t ocp_nlp_dynamics_cont_dims_calculate_size(void *config); -// -void *ocp_nlp_dynamics_cont_dims_assign(void *config, void *raw_memory); -// -void ocp_nlp_dynamics_cont_dims_set(void *config_, void *dims_, const char *field, int* value); - -/************************************************ - * options - ************************************************/ - -typedef struct -{ - void *sim_solver; - int compute_adj; - int compute_hess; -} ocp_nlp_dynamics_cont_opts; - -// -acados_size_t ocp_nlp_dynamics_cont_opts_calculate_size(void *config, void *dims); -// -void *ocp_nlp_dynamics_cont_opts_assign(void *config, void *dims, void *raw_memory); -// -void ocp_nlp_dynamics_cont_opts_initialize_default(void *config, void *dims, void *opts); -// -void ocp_nlp_dynamics_cont_opts_update(void *config, void *dims, void *opts); -// -void ocp_nlp_dynamics_cont_opts_set(void *config, void *opts, const char *field, void* value); - - - -/************************************************ - * memory - ************************************************/ - -typedef struct -{ - struct blasfeo_dvec fun; - struct blasfeo_dvec adj; - struct blasfeo_dvec *ux; // pointer to ux in nlp_out at current stage - struct blasfeo_dvec *tmp_ux; // pointer to ux in tmp_nlp_out at current stage - struct blasfeo_dvec *ux1; // pointer to ux in nlp_out at next stage - struct blasfeo_dvec *tmp_ux1; // pointer to ux in tmp_nlp_out at next stage - struct blasfeo_dvec *pi; // pointer to pi in nlp_out at current stage - struct blasfeo_dvec *tmp_pi; // pointer to pi in tmp_nlp_out at current stage - struct blasfeo_dmat *BAbt; // pointer to BAbt in qp_in - struct blasfeo_dmat *RSQrq; // pointer to RSQrq in qp_in - struct blasfeo_dvec *z_alg; // pointer to output z at t = 0 - bool *set_sim_guess; // indicate if initialization for integrator is set from outside - struct blasfeo_dvec *sim_guess; // initializations for integrator - // struct blasfeo_dvec *z; // pointer to (input) z in nlp_out at current stage - struct blasfeo_dmat *dzduxt; // pointer to dzdux transposed - void *sim_solver; // sim solver memory -} ocp_nlp_dynamics_cont_memory; - -// -acados_size_t ocp_nlp_dynamics_cont_memory_calculate_size(void *config, void *dims, void *opts); -// -void *ocp_nlp_dynamics_cont_memory_assign(void *config, void *dims, void *opts, void *raw_memory); -// -struct blasfeo_dvec *ocp_nlp_dynamics_cont_memory_get_fun_ptr(void *memory); -// -struct blasfeo_dvec *ocp_nlp_dynamics_cont_memory_get_adj_ptr(void *memory); -// -void ocp_nlp_dynamics_cont_memory_set_ux_ptr(struct blasfeo_dvec *ux, void *memory); -// -void ocp_nlp_dynamics_cont_memory_set_tmp_ux_ptr(struct blasfeo_dvec *tmp_ux, void *memory); -// -void ocp_nlp_dynamics_cont_memory_set_ux1_ptr(struct blasfeo_dvec *ux1, void *memory); -// -void ocp_nlp_dynamics_cont_memory_set_tmp_ux1_ptr(struct blasfeo_dvec *tmp_ux1, void *memory); -// -void ocp_nlp_dynamics_cont_memory_set_pi_ptr(struct blasfeo_dvec *pi, void *memory); -// -void ocp_nlp_dynamics_cont_memory_set_tmp_pi_ptr(struct blasfeo_dvec *tmp_pi, void *memory); -// -void ocp_nlp_dynamics_cont_memory_set_BAbt_ptr(struct blasfeo_dmat *BAbt, void *memory); - - - -/************************************************ - * workspace - ************************************************/ - -typedef struct -{ - struct blasfeo_dmat hess; - sim_in *sim_in; - sim_out *sim_out; - void *sim_solver; // sim solver workspace -} ocp_nlp_dynamics_cont_workspace; - -acados_size_t ocp_nlp_dynamics_cont_workspace_calculate_size(void *config, void *dims, void *opts); - - - -/************************************************ - * model - ************************************************/ - -typedef struct -{ - void *sim_model; - // double *state_transition; // TODO - double T; // simulation time -} ocp_nlp_dynamics_cont_model; - -// -acados_size_t ocp_nlp_dynamics_cont_model_calculate_size(void *config, void *dims); -// -void *ocp_nlp_dynamics_cont_model_assign(void *config, void *dims, void *raw_memory); -// -void ocp_nlp_dynamics_cont_model_set(void *config_, void *dims_, void *model_, const char *field, void *value); - - - -/************************************************ - * functions - ************************************************/ - -// -void ocp_nlp_dynamics_cont_config_initialize_default(void *config); -// -void ocp_nlp_dynamics_cont_initialize(void *config_, void *dims, void *model_, void *opts, void *mem, void *work_); -// -void ocp_nlp_dynamics_cont_update_qp_matrices(void *config_, void *dims, void *model_, void *opts, void *mem, void *work_); -// -void ocp_nlp_dynamics_cont_compute_fun(void *config_, void *dims, void *model_, void *opts, void *mem, void *work_); -// -int ocp_nlp_dynamics_cont_precompute(void *config_, void *dims, void *model_, void *opts_, void *mem_, void *work_); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_DYNAMICS_CONT_H_ -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_disc.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_disc.h deleted file mode 100644 index 6ea26a7010..0000000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_disc.h +++ /dev/null @@ -1,192 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \addtogroup ocp_nlp -/// @{ -/// \addtogroup ocp_nlp_dynamics -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_DYNAMICS_DISC_H_ -#define ACADOS_OCP_NLP_OCP_NLP_DYNAMICS_DISC_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// blasfeo -#include "blasfeo/include/blasfeo_common.h" - -// acados -#include "acados/ocp_nlp/ocp_nlp_dynamics_common.h" -#include "acados/utils/external_function_generic.h" -#include "acados/utils/types.h" - -/************************************************ - * dims - ************************************************/ - -typedef struct -{ - int nx; // number of states at the current stage - int nu; // number of inputs at the current stage - int nx1; // number of states at the next stage - int nu1; // number of inputes at the next stage -} ocp_nlp_dynamics_disc_dims; - -// -acados_size_t ocp_nlp_dynamics_disc_dims_calculate_size(void *config); -// -void *ocp_nlp_dynamics_disc_dims_assign(void *config, void *raw_memory); -// -void ocp_nlp_dynamics_disc_dims_set(void *config_, void *dims_, const char *dim, int* value); - - -/************************************************ - * options - ************************************************/ - -typedef struct -{ - int compute_adj; - int compute_hess; -} ocp_nlp_dynamics_disc_opts; - -// -acados_size_t ocp_nlp_dynamics_disc_opts_calculate_size(void *config, void *dims); -// -void *ocp_nlp_dynamics_disc_opts_assign(void *config, void *dims, void *raw_memory); -// -void ocp_nlp_dynamics_disc_opts_initialize_default(void *config, void *dims, void *opts); -// -void ocp_nlp_dynamics_disc_opts_update(void *config, void *dims, void *opts); -// -int ocp_nlp_dynamics_disc_precompute(void *config_, void *dims, void *model_, void *opts_, - void *mem_, void *work_); - - -/************************************************ - * memory - ************************************************/ - -typedef struct -{ - struct blasfeo_dvec fun; - struct blasfeo_dvec adj; - struct blasfeo_dvec *ux; // pointer to ux in nlp_out at current stage - struct blasfeo_dvec *tmp_ux; // pointer to ux in tmp_nlp_out at current stage - struct blasfeo_dvec *ux1; // pointer to ux in nlp_out at next stage - struct blasfeo_dvec *tmp_ux1;// pointer to ux in tmp_nlp_out at next stage - struct blasfeo_dvec *pi; // pointer to pi in nlp_out at current stage - struct blasfeo_dvec *tmp_pi; // pointer to pi in tmp_nlp_out at current stage - struct blasfeo_dmat *BAbt; // pointer to BAbt in qp_in - struct blasfeo_dmat *RSQrq; // pointer to RSQrq in qp_in -} ocp_nlp_dynamics_disc_memory; - -// -acados_size_t ocp_nlp_dynamics_disc_memory_calculate_size(void *config, void *dims, void *opts); -// -void *ocp_nlp_dynamics_disc_memory_assign(void *config, void *dims, void *opts, void *raw_memory); -// -struct blasfeo_dvec *ocp_nlp_dynamics_disc_memory_get_fun_ptr(void *memory); -// -struct blasfeo_dvec *ocp_nlp_dynamics_disc_memory_get_adj_ptr(void *memory); -// -void ocp_nlp_dynamics_disc_memory_set_ux_ptr(struct blasfeo_dvec *ux, void *memory); -// -void ocp_nlp_dynamics_disc_memory_set_tmp_ux_ptr(struct blasfeo_dvec *tmp_ux, void *memory); -// -void ocp_nlp_dynamics_disc_memory_set_ux1_ptr(struct blasfeo_dvec *ux1, void *memory); -// -void ocp_nlp_dynamics_disc_memory_set_tmp_ux1_ptr(struct blasfeo_dvec *tmp_ux1, void *memory); -// -void ocp_nlp_dynamics_disc_memory_set_pi_ptr(struct blasfeo_dvec *pi, void *memory); -// -void ocp_nlp_dynamics_disc_memory_set_tmp_pi_ptr(struct blasfeo_dvec *tmp_pi, void *memory); -// -void ocp_nlp_dynamics_disc_memory_set_BAbt_ptr(struct blasfeo_dmat *BAbt, void *memory); - - - -/************************************************ - * workspace - ************************************************/ - -typedef struct -{ - struct blasfeo_dmat tmp_nv_nv; -} ocp_nlp_dynamics_disc_workspace; - -acados_size_t ocp_nlp_dynamics_disc_workspace_calculate_size(void *config, void *dims, void *opts); - - - -/************************************************ - * model - ************************************************/ - -typedef struct -{ - external_function_generic *disc_dyn_fun; - external_function_generic *disc_dyn_fun_jac; - external_function_generic *disc_dyn_fun_jac_hess; -} ocp_nlp_dynamics_disc_model; - -// -acados_size_t ocp_nlp_dynamics_disc_model_calculate_size(void *config, void *dims); -// -void *ocp_nlp_dynamics_disc_model_assign(void *config, void *dims, void *raw_memory); -// -void ocp_nlp_dynamics_disc_model_set(void *config_, void *dims_, void *model_, const char *field, void *value); - - - -/************************************************ - * functions - ************************************************/ - -// -void ocp_nlp_dynamics_disc_config_initialize_default(void *config); -// -void ocp_nlp_dynamics_disc_initialize(void *config_, void *dims, void *model_, void *opts, void *mem, void *work_); -// -void ocp_nlp_dynamics_disc_update_qp_matrices(void *config_, void *dims, void *model_, void *opts, void *mem, void *work_); -// -void ocp_nlp_dynamics_disc_compute_fun(void *config_, void *dims, void *model_, void *opts, void *mem, void *work_); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_DYNAMICS_DISC_H_ -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_common.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_common.h deleted file mode 100644 index 9388f3fd24..0000000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_common.h +++ /dev/null @@ -1,122 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \ingroup ocp_nlp -/// @{ - -/// \defgroup ocp_nlp_reg ocp_nlp_reg -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_REG_COMMON_H_ -#define ACADOS_OCP_NLP_OCP_NLP_REG_COMMON_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/ocp_qp/ocp_qp_common.h" - - - -/* dims */ - -//typedef ocp_qp_dims ocp_nlp_reg_dims; -typedef struct -{ - int *nx; - int *nu; - int *nbu; - int *nbx; - int *ng; - int N; -} ocp_nlp_reg_dims; - -// -acados_size_t ocp_nlp_reg_dims_calculate_size(int N); -// -ocp_nlp_reg_dims *ocp_nlp_reg_dims_assign(int N, void *raw_memory); -// -void ocp_nlp_reg_dims_set(void *config_, ocp_nlp_reg_dims *dims, int stage, char *field, int* value); - - - -/* config */ - -typedef struct -{ - /* dims */ - acados_size_t (*dims_calculate_size)(int N); - ocp_nlp_reg_dims *(*dims_assign)(int N, void *raw_memory); - void (*dims_set)(void *config, ocp_nlp_reg_dims *dims, int stage, char *field, int *value); - /* opts */ - acados_size_t (*opts_calculate_size)(void); - void *(*opts_assign)(void *raw_memory); - void (*opts_initialize_default)(void *config, ocp_nlp_reg_dims *dims, void *opts); - void (*opts_set)(void *config, ocp_nlp_reg_dims *dims, void *opts, char *field, void* value); - /* memory */ - acados_size_t (*memory_calculate_size)(void *config, ocp_nlp_reg_dims *dims, void *opts); - void *(*memory_assign)(void *config, ocp_nlp_reg_dims *dims, void *opts, void *raw_memory); - void (*memory_set)(void *config, ocp_nlp_reg_dims *dims, void *memory, char *field, void* value); - void (*memory_set_RSQrq_ptr)(ocp_nlp_reg_dims *dims, struct blasfeo_dmat *mat, void *memory); - void (*memory_set_rq_ptr)(ocp_nlp_reg_dims *dims, struct blasfeo_dvec *vec, void *memory); - void (*memory_set_BAbt_ptr)(ocp_nlp_reg_dims *dims, struct blasfeo_dmat *mat, void *memory); - void (*memory_set_b_ptr)(ocp_nlp_reg_dims *dims, struct blasfeo_dvec *vec, void *memory); - void (*memory_set_idxb_ptr)(ocp_nlp_reg_dims *dims, int **idxb, void *memory); - void (*memory_set_DCt_ptr)(ocp_nlp_reg_dims *dims, struct blasfeo_dmat *mat, void *memory); - void (*memory_set_ux_ptr)(ocp_nlp_reg_dims *dims, struct blasfeo_dvec *vec, void *memory); - void (*memory_set_pi_ptr)(ocp_nlp_reg_dims *dims, struct blasfeo_dvec *vec, void *memory); - void (*memory_set_lam_ptr)(ocp_nlp_reg_dims *dims, struct blasfeo_dvec *vec, void *memory); - /* functions */ - void (*regularize_hessian)(void *config, ocp_nlp_reg_dims *dims, void *opts, void *memory); - void (*correct_dual_sol)(void *config, ocp_nlp_reg_dims *dims, void *opts, void *memory); -} ocp_nlp_reg_config; - -// -acados_size_t ocp_nlp_reg_config_calculate_size(void); -// -void *ocp_nlp_reg_config_assign(void *raw_memory); - - - -/* regularization help functions */ -void acados_reconstruct_A(int dim, double *A, double *V, double *d); -void acados_mirror(int dim, double *A, double *V, double *d, double *e, double epsilon); -void acados_project(int dim, double *A, double *V, double *d, double *e, double epsilon); - - - -#ifdef __cplusplus -} -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_REG_COMMON_H_ -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_convexify.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_convexify.h deleted file mode 100644 index cb523525e1..0000000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_convexify.h +++ /dev/null @@ -1,146 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \addtogroup ocp_nlp -/// @{ -/// \addtogroup ocp_nlp_reg -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_REG_CONVEXIFY_H_ -#define ACADOS_OCP_NLP_OCP_NLP_REG_CONVEXIFY_H_ - -#ifdef __cplusplus -extern "C" { -#endif - - - -// blasfeo -#include "blasfeo/include/blasfeo_common.h" - -// acados -#include "acados/ocp_nlp/ocp_nlp_reg_common.h" - - - -/************************************************ - * dims - ************************************************/ - -// use the functions in ocp_nlp_reg_common - -/************************************************ - * options - ************************************************/ - -typedef struct -{ - double delta; - double epsilon; -// double gamma; // 0.0 -} ocp_nlp_reg_convexify_opts; - -// -acados_size_t ocp_nlp_reg_convexify_opts_calculate_size(void); -// -void *ocp_nlp_reg_convexify_opts_assign(void *raw_memory); -// -void ocp_nlp_reg_convexify_opts_initialize_default(void *config_, ocp_nlp_reg_dims *dims, void *opts_); -// -void ocp_nlp_reg_convexify_opts_set(void *config_, ocp_nlp_reg_dims *dims, void *opts_, char *field, void* value); - - - -/************************************************ - * memory - ************************************************/ - -typedef struct { - double *R; - double *V; // TODO move to workspace - double *d; // TODO move to workspace - double *e; // TODO move to workspace - double *reg_hess; // TODO move to workspace - - struct blasfeo_dmat Q_tilde; - struct blasfeo_dmat Q_bar; - struct blasfeo_dmat BAQ; - struct blasfeo_dmat L; - struct blasfeo_dmat delta_eye; - struct blasfeo_dmat St_copy; - - struct blasfeo_dmat *original_RSQrq; - struct blasfeo_dmat tmp_RSQ; - - struct blasfeo_dvec tmp_nuxM; - struct blasfeo_dvec tmp_nbgM; - -// struct blasfeo_dvec grad; -// struct blasfeo_dvec b2; - - // giaf's - struct blasfeo_dmat **RSQrq; // pointer to RSQrq in qp_in - struct blasfeo_dvec **rq; // pointer to rq in qp_in - struct blasfeo_dmat **BAbt; // pointer to BAbt in qp_in - struct blasfeo_dvec **b; // pointer to b in qp_in - struct blasfeo_dmat **DCt; // pointer to DCt in qp_in - struct blasfeo_dvec **ux; // pointer to ux in qp_out - struct blasfeo_dvec **pi; // pointer to pi in qp_out - struct blasfeo_dvec **lam; // pointer to lam in qp_out - int **idxb; // pointer to idxb in qp_in - -} ocp_nlp_reg_convexify_memory; - -// -acados_size_t ocp_nlp_reg_convexify_calculate_memory_size(void *config, ocp_nlp_reg_dims *dims, void *opts); -// -void *ocp_nlp_reg_convexify_assign_memory(void *config, ocp_nlp_reg_dims *dims, void *opts, void *raw_memory); - -/************************************************ - * workspace - ************************************************/ - - // TODO - -/************************************************ - * functions - ************************************************/ - -// -void ocp_nlp_reg_convexify_config_initialize_default(ocp_nlp_reg_config *config); - -#ifdef __cplusplus -} -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_REG_CONVEXIFY_H_ -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_mirror.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_mirror.h deleted file mode 100644 index 84a023cb69..0000000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_mirror.h +++ /dev/null @@ -1,121 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \addtogroup ocp_nlp -/// @{ -/// \addtogroup ocp_nlp_reg -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_REG_MIRROR_H_ -#define ACADOS_OCP_NLP_OCP_NLP_REG_MIRROR_H_ - -#ifdef __cplusplus -extern "C" { -#endif - - - -// blasfeo -#include "blasfeo/include/blasfeo_common.h" - -// acados -#include "acados/ocp_nlp/ocp_nlp_reg_common.h" - - - -/************************************************ - * dims - ************************************************/ - -// use the functions in ocp_nlp_reg_common - -/************************************************ - * options - ************************************************/ - -typedef struct -{ - double epsilon; -} ocp_nlp_reg_mirror_opts; - -// -acados_size_t ocp_nlp_reg_mirror_opts_calculate_size(void); -// -void *ocp_nlp_reg_mirror_opts_assign(void *raw_memory); -// -void ocp_nlp_reg_mirror_opts_initialize_default(void *config_, ocp_nlp_reg_dims *dims, void *opts_); -// -void ocp_nlp_reg_mirror_opts_set(void *config_, ocp_nlp_reg_dims *dims, void *opts_, char *field, void* value); - - - -/************************************************ - * memory - ************************************************/ - -typedef struct -{ - double *reg_hess; // TODO move to workspace - double *V; // TODO move to workspace - double *d; // TODO move to workspace - double *e; // TODO move to workspace - - // giaf's - struct blasfeo_dmat **RSQrq; // pointer to RSQrq in qp_in -} ocp_nlp_reg_mirror_memory; - -// -acados_size_t ocp_nlp_reg_mirror_memory_calculate_size(void *config, ocp_nlp_reg_dims *dims, void *opts); -// -void *ocp_nlp_reg_mirror_memory_assign(void *config, ocp_nlp_reg_dims *dims, void *opts, void *raw_memory); - -/************************************************ - * workspace - ************************************************/ - - // TODO - -/************************************************ - * functions - ************************************************/ - -// -void ocp_nlp_reg_mirror_config_initialize_default(ocp_nlp_reg_config *config); - - - -#ifdef __cplusplus -} -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_REG_MIRROR_H_ -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_noreg.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_noreg.h deleted file mode 100644 index b571f3bac1..0000000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_noreg.h +++ /dev/null @@ -1,106 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \addtogroup ocp_nlp -/// @{ -/// \addtogroup ocp_nlp_reg -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_REG_NOREG_H_ -#define ACADOS_OCP_NLP_OCP_NLP_REG_NOREG_H_ - -#ifdef __cplusplus -extern "C" { -#endif - - - -// blasfeo -#include "blasfeo/include/blasfeo_common.h" - -// acados -#include "acados/ocp_nlp/ocp_nlp_reg_common.h" - - - -/************************************************ - * dims - ************************************************/ - -// use the functions in ocp_nlp_reg_common - - -/************************************************ - * options - ************************************************/ - -// -acados_size_t ocp_nlp_reg_noreg_opts_calculate_size(void); -// -void *ocp_nlp_reg_noreg_opts_assign(void *raw_memory); -// -void ocp_nlp_reg_noreg_opts_initialize_default(void *config_, ocp_nlp_reg_dims *dims, void *opts_); -// -void ocp_nlp_reg_noreg_opts_set(void *config_, ocp_nlp_reg_dims *dims, void *opts_, char *field, void* value); - - - -/************************************************ - * memory - ************************************************/ -// -acados_size_t ocp_nlp_reg_noreg_memory_calculate_size(void *config, ocp_nlp_reg_dims *dims, void *opts); -// -void *ocp_nlp_reg_noreg_memory_assign(void *config, ocp_nlp_reg_dims *dims, void *opts, void *raw_memory); - -/************************************************ - * workspace - ************************************************/ - -// not needed - -/************************************************ - * functions - ************************************************/ - -// -void ocp_nlp_reg_noreg_config_initialize_default(ocp_nlp_reg_config *config); - - - -#ifdef __cplusplus -} -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_REG_NOREG_H_ - -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_project.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_project.h deleted file mode 100644 index 682ea206dc..0000000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_project.h +++ /dev/null @@ -1,121 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \addtogroup ocp_nlp -/// @{ -/// \addtogroup ocp_nlp_reg -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_REG_PROJECT_H_ -#define ACADOS_OCP_NLP_OCP_NLP_REG_PROJECT_H_ - -#ifdef __cplusplus -extern "C" { -#endif - - - -// blasfeo -#include "blasfeo/include/blasfeo_common.h" - -// acados -#include "acados/ocp_nlp/ocp_nlp_reg_common.h" - - - -/************************************************ - * dims - ************************************************/ - -// use the functions in ocp_nlp_reg_common - -/************************************************ - * options - ************************************************/ - -typedef struct -{ - double epsilon; -} ocp_nlp_reg_project_opts; - -// -acados_size_t ocp_nlp_reg_project_opts_calculate_size(void); -// -void *ocp_nlp_reg_project_opts_assign(void *raw_memory); -// -void ocp_nlp_reg_project_opts_initialize_default(void *config_, ocp_nlp_reg_dims *dims, void *opts_); -// -void ocp_nlp_reg_project_opts_set(void *config_, ocp_nlp_reg_dims *dims, void *opts_, char *field, void* value); - - - -/************************************************ - * memory - ************************************************/ - -typedef struct -{ - double *reg_hess; // TODO move to workspace - double *V; // TODO move to workspace - double *d; // TODO move to workspace - double *e; // TODO move to workspace - - // giaf's - struct blasfeo_dmat **RSQrq; // pointer to RSQrq in qp_in -} ocp_nlp_reg_project_memory; - -// -acados_size_t ocp_nlp_reg_project_memory_calculate_size(void *config, ocp_nlp_reg_dims *dims, void *opts); -// -void *ocp_nlp_reg_project_memory_assign(void *config, ocp_nlp_reg_dims *dims, void *opts, void *raw_memory); - -/************************************************ - * workspace - ************************************************/ - - // TODO - -/************************************************ - * functions - ************************************************/ - -// -void ocp_nlp_reg_project_config_initialize_default(ocp_nlp_reg_config *config); - - - -#ifdef __cplusplus -} -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_REG_PROJECT_H_ -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_project_reduc_hess.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_project_reduc_hess.h deleted file mode 100644 index 7e12952c15..0000000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_project_reduc_hess.h +++ /dev/null @@ -1,132 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \addtogroup ocp_nlp -/// @{ -/// \addtogroup ocp_nlp_reg -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_REG_PROJECT_REDUC_HESS_H_ -#define ACADOS_OCP_NLP_OCP_NLP_REG_PROJECT_REDUC_HESS_H_ - -#ifdef __cplusplus -extern "C" { -#endif - - - -// blasfeo -#include "blasfeo/include/blasfeo_common.h" - -// acados -#include "acados/ocp_nlp/ocp_nlp_reg_common.h" - - - -/************************************************ - * dims - ************************************************/ - -// use the functions in ocp_nlp_reg_common - -/************************************************ - * options - ************************************************/ - -typedef struct -{ - double thr_eig; - double min_eig; - double min_pivot; - int pivoting; -} ocp_nlp_reg_project_reduc_hess_opts; - -// -acados_size_t ocp_nlp_reg_project_reduc_hess_opts_calculate_size(void); -// -void *ocp_nlp_reg_project_reduc_hess_opts_assign(void *raw_memory); -// -void ocp_nlp_reg_project_reduc_hess_opts_initialize_default(void *config_, ocp_nlp_reg_dims *dims, void *opts_); -// -void ocp_nlp_reg_project_reduc_hess_opts_set(void *config_, ocp_nlp_reg_dims *dims, void *opts_, char *field, void* value); - - - -/************************************************ - * memory - ************************************************/ - -typedef struct -{ - double *reg_hess; // TODO move to workspace - double *V; // TODO move to workspace - double *d; // TODO move to workspace - double *e; // TODO move to workspace - - // giaf's - struct blasfeo_dmat L; // TODO move to workspace - struct blasfeo_dmat L2; // TODO move to workspace - struct blasfeo_dmat L3; // TODO move to workspace - struct blasfeo_dmat Ls; // TODO move to workspace - struct blasfeo_dmat P; // TODO move to workspace - struct blasfeo_dmat AL; // TODO move to workspace - - struct blasfeo_dmat **RSQrq; // pointer to RSQrq in qp_in - struct blasfeo_dmat **BAbt; // pointer to RSQrq in qp_in -} ocp_nlp_reg_project_reduc_hess_memory; - -// -acados_size_t ocp_nlp_reg_project_reduc_hess_memory_calculate_size(void *config, ocp_nlp_reg_dims *dims, void *opts); -// -void *ocp_nlp_reg_project_reduc_hess_memory_assign(void *config, ocp_nlp_reg_dims *dims, void *opts, void *raw_memory); - -/************************************************ - * workspace - ************************************************/ - - // TODO - -/************************************************ - * functions - ************************************************/ - -// -void ocp_nlp_reg_project_reduc_hess_config_initialize_default(ocp_nlp_reg_config *config); - - - -#ifdef __cplusplus -} -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_REG_PROJECT_REDUC_HESS_H_ -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_sqp.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_sqp.h deleted file mode 100644 index fdb96417f9..0000000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_sqp.h +++ /dev/null @@ -1,170 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \addtogroup ocp_nlp -/// @{ -/// \addtogroup ocp_nlp_solver -/// @{ -/// \addtogroup ocp_nlp_sqp ocp_nlp_sqp -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_SQP_H_ -#define ACADOS_OCP_NLP_OCP_NLP_SQP_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// acados -#include "acados/ocp_nlp/ocp_nlp_common.h" -#include "acados/utils/types.h" - - - -/************************************************ - * options - ************************************************/ - -typedef struct -{ - ocp_nlp_opts *nlp_opts; - double tol_stat; // exit tolerance on stationarity condition - double tol_eq; // exit tolerance on equality constraints - double tol_ineq; // exit tolerance on inequality constraints - double tol_comp; // exit tolerance on complementarity condition - int max_iter; - int ext_qp_res; // compute external QP residuals (i.e. at SQP level) at each SQP iteration (for debugging) - int qp_warm_start; // qp_warm_start in all but the first sqp iterations - bool warm_start_first_qp; // to set qp_warm_start in first iteration - int rti_phase; // only phase 0 at the moment - int initialize_t_slacks; // 0-false or 1-true - -} ocp_nlp_sqp_opts; - -// -acados_size_t ocp_nlp_sqp_opts_calculate_size(void *config, void *dims); -// -void *ocp_nlp_sqp_opts_assign(void *config, void *dims, void *raw_memory); -// -void ocp_nlp_sqp_opts_initialize_default(void *config, void *dims, void *opts); -// -void ocp_nlp_sqp_opts_update(void *config, void *dims, void *opts); -// -void ocp_nlp_sqp_opts_set(void *config_, void *opts_, const char *field, void* value); -// -void ocp_nlp_sqp_opts_set_at_stage(void *config_, void *opts_, size_t stage, const char *field, void* value); - - - -/************************************************ - * memory - ************************************************/ - -typedef struct -{ - // nlp memory - ocp_nlp_memory *nlp_mem; - - double time_qp_sol; - double time_qp_solver_call; - double time_qp_xcond; - double time_lin; - double time_reg; - double time_tot; - double time_glob; - double time_sim; - double time_sim_la; - double time_sim_ad; - double time_solution_sensitivities; - - // statistics - double *stat; - int stat_m; - int stat_n; - - int status; - int sqp_iter; - -} ocp_nlp_sqp_memory; - -// -acados_size_t ocp_nlp_sqp_memory_calculate_size(void *config, void *dims, void *opts_); -// -void *ocp_nlp_sqp_memory_assign(void *config, void *dims, void *opts_, void *raw_memory); -// -void ocp_nlp_sqp_memory_reset_qp_solver(void *config_, void *dims_, void *nlp_in_, void *nlp_out_, - void *opts_, void *mem_, void *work_); - - -/************************************************ - * workspace - ************************************************/ - -typedef struct -{ - ocp_nlp_workspace *nlp_work; - - // temp QP in & out (to be used as workspace in param sens) - ocp_qp_in *tmp_qp_in; - ocp_qp_out *tmp_qp_out; - - // qp residuals - ocp_qp_res *qp_res; - ocp_qp_res_ws *qp_res_ws; - -} ocp_nlp_sqp_workspace; - -// -acados_size_t ocp_nlp_sqp_workspace_calculate_size(void *config, void *dims, void *opts_); - - - -/************************************************ - * functions - ************************************************/ - -// -int ocp_nlp_sqp(void *config, void *dims, void *nlp_in, void *nlp_out, - void *args, void *mem, void *work_); -// -void ocp_nlp_sqp_config_initialize_default(void *config_); -// -int ocp_nlp_sqp_precompute(void *config_, void *dims_, void *nlp_in_, void *nlp_out_, - void *opts_, void *mem_, void *work_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_SQP_H_ -/// @} -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_sqp_rti.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_sqp_rti.h deleted file mode 100644 index 364d0f4717..0000000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_sqp_rti.h +++ /dev/null @@ -1,163 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \addtogroup ocp_nlp -/// @{ -/// \addtogroup ocp_nlp_solver -/// @{ -/// \addtogroup ocp_nlp_sqp_rti ocp_nlp_sqp_rti -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_SQP_RTI_H_ -#define ACADOS_OCP_NLP_OCP_NLP_SQP_RTI_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// acados -#include "acados/ocp_nlp/ocp_nlp_common.h" -#include "acados/utils/types.h" - - - -/************************************************ - * options - ************************************************/ - -typedef struct -{ - ocp_nlp_opts *nlp_opts; - int compute_dual_sol; - int ext_qp_res; // compute external QP residuals (i.e. at SQP level) at each SQP iteration (for debugging) - int qp_warm_start; // NOTE: this is not actually setting the warm_start! Just for compatibility with sqp. - bool warm_start_first_qp; // to set qp_warm_start in first iteration - int rti_phase; // phase of RTI. Possible values 1 (preparation), 2 (feedback) 0 (both) - -} ocp_nlp_sqp_rti_opts; - -// -acados_size_t ocp_nlp_sqp_rti_opts_calculate_size(void *config_, void *dims_); -// -void *ocp_nlp_sqp_rti_opts_assign(void *config_, void *dims_, void *raw_memory); -// -void ocp_nlp_sqp_rti_opts_initialize_default(void *config_, void *dims_, void *opts_); -// -void ocp_nlp_sqp_rti_opts_update(void *config_, void *dims_, void *opts_); -// -void ocp_nlp_sqp_rti_opts_set(void *config_, void *opts_, const char *field, void* value); -// -void ocp_nlp_sqp_rti_opts_set_at_stage(void *config_, void *opts_, size_t stage, - const char *field, void* value); - - - -/************************************************ - * memory - ************************************************/ - -typedef struct -{ - // nlp memory - ocp_nlp_memory *nlp_mem; - - double time_qp_sol; - double time_qp_solver_call; - double time_qp_xcond; - double time_lin; - double time_reg; - double time_tot; - double time_glob; - double time_solution_sensitivities; - - // statistics - double *stat; - int stat_m; - int stat_n; - - int status; - -} ocp_nlp_sqp_rti_memory; - -// -acados_size_t ocp_nlp_sqp_rti_memory_calculate_size(void *config_, void *dims_, void *opts_); -// -void *ocp_nlp_sqp_rti_memory_assign(void *config_, void *dims_, void *opts_, - void *raw_memory); - - - -/************************************************ - * workspace - ************************************************/ - -typedef struct -{ - ocp_nlp_workspace *nlp_work; - - // temp QP in & out (to be used as workspace in param sens) - ocp_qp_in *tmp_qp_in; - ocp_qp_out *tmp_qp_out; - - // qp residuals - ocp_qp_res *qp_res; - ocp_qp_res_ws *qp_res_ws; - - -} ocp_nlp_sqp_rti_workspace; - -// -acados_size_t ocp_nlp_sqp_rti_workspace_calculate_size(void *config_, void *dims_, void *opts_); - - - -/************************************************ - * functions - ************************************************/ -// -int ocp_nlp_sqp_rti(void *config_, void *dims_, void *nlp_in_, void *nlp_out_, - void *opts_, void *mem_, void *work_); -// -void ocp_nlp_sqp_rti_config_initialize_default(void *config_); -// -int ocp_nlp_sqp_rti_precompute(void *config_, void *dims_, - void *nlp_in_, void *nlp_out_, void *opts_, void *mem_, void *work_); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_SQP_RTI_H_ -/// @} -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_common.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_common.h deleted file mode 100644 index d1a45635e4..0000000000 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_common.h +++ /dev/null @@ -1,180 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_OCP_QP_OCP_QP_COMMON_H_ -#define ACADOS_OCP_QP_OCP_QP_COMMON_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// hpipm -#include "hpipm/include/hpipm_d_ocp_qp.h" -#include "hpipm/include/hpipm_d_ocp_qp_dim.h" -#include "hpipm/include/hpipm_d_ocp_qp_res.h" -#include "hpipm/include/hpipm_d_ocp_qp_sol.h" -// acados -#include "acados/utils/types.h" - - - -typedef struct d_ocp_qp_dim ocp_qp_dims; -typedef struct d_ocp_qp ocp_qp_in; -typedef struct d_ocp_qp_sol ocp_qp_out; -typedef struct d_ocp_qp_res ocp_qp_res; -typedef struct d_ocp_qp_res_ws ocp_qp_res_ws; - - - -#ifndef QP_SOLVER_CONFIG_ -#define QP_SOLVER_CONFIG_ -typedef struct -{ - void (*dims_set)(void *config_, void *dims_, int stage, const char *field, int* value); - acados_size_t (*opts_calculate_size)(void *config, void *dims); - void *(*opts_assign)(void *config, void *dims, void *raw_memory); - void (*opts_initialize_default)(void *config, void *dims, void *opts); - void (*opts_update)(void *config, void *dims, void *opts); - void (*opts_set)(void *config_, void *opts_, const char *field, void* value); - acados_size_t (*memory_calculate_size)(void *config, void *dims, void *opts); - void *(*memory_assign)(void *config, void *dims, void *opts, void *raw_memory); - void (*memory_get)(void *config_, void *mem_, const char *field, void* value); - acados_size_t (*workspace_calculate_size)(void *config, void *dims, void *opts); - int (*evaluate)(void *config, void *qp_in, void *qp_out, void *opts, void *mem, void *work); - void (*memory_reset)(void *config, void *qp_in, void *qp_out, void *opts, void *mem, void *work); - void (*eval_sens)(void *config, void *qp_in, void *qp_out, void *opts, void *mem, void *work); -} qp_solver_config; -#endif - - - -typedef struct -{ - acados_size_t (*dims_calculate_size)(void *config, int N); - void *(*dims_assign)(void *config, int N, void *raw_memory); - void (*dims_set)(void *config, void *dims_, int stage, const char *field, int* value); - void (*dims_get)(void *config, void *dims, const char *field, void* value); - // TODO add config everywhere !!!!! - acados_size_t (*opts_calculate_size)(void *dims); - void *(*opts_assign)(void *dims, void *raw_memory); - void (*opts_initialize_default)(void *dims, void *opts); - void (*opts_update)(void *dims, void *opts); - void (*opts_set)(void *opts_, const char *field, void* value); - acados_size_t (*memory_calculate_size)(void *dims, void *opts); - void *(*memory_assign)(void *dims, void *opts, void *raw_memory); - void (*memory_get)(void *config, void *mem, const char *field, void* value); - acados_size_t (*workspace_calculate_size)(void *dims, void *opts); - int (*condensing)(void *qp_in, void *qp_out, void *opts, void *mem, void *work); - int (*condensing_rhs)(void *qp_in, void *qp_out, void *opts, void *mem, void *work); - int (*expansion)(void *qp_in, void *qp_out, void *opts, void *mem, void *work); -} ocp_qp_xcond_config; - - - -/// Struct containing metrics of the qp solver. -#ifndef QP_INFO_ -#define QP_INFO_ -typedef struct -{ - double solve_QP_time; - double condensing_time; - double interface_time; - double total_time; - int num_iter; - int t_computed; -} qp_info; -#endif - - - -/* config */ -// -acados_size_t ocp_qp_solver_config_calculate_size(); -// -qp_solver_config *ocp_qp_solver_config_assign(void *raw_memory); -// -acados_size_t ocp_qp_condensing_config_calculate_size(); -// -ocp_qp_xcond_config *ocp_qp_condensing_config_assign(void *raw_memory); - - -/* dims */ -// -acados_size_t ocp_qp_dims_calculate_size(int N); -// -ocp_qp_dims *ocp_qp_dims_assign(int N, void *raw_memory); -// -void ocp_qp_dims_set(void *config_, void *dims, int stage, const char *field, int* value); -// -void ocp_qp_dims_get(void *config_, void *dims, int stage, const char *field, int* value); - - -/* in */ -// -acados_size_t ocp_qp_in_calculate_size(ocp_qp_dims *dims); -// -ocp_qp_in *ocp_qp_in_assign(ocp_qp_dims *dims, void *raw_memory); - - -/* out */ -// -acados_size_t ocp_qp_out_calculate_size(ocp_qp_dims *dims); -// -ocp_qp_out *ocp_qp_out_assign(ocp_qp_dims *dims, void *raw_memory); - -/* res */ -// -acados_size_t ocp_qp_res_calculate_size(ocp_qp_dims *dims); -// -ocp_qp_res *ocp_qp_res_assign(ocp_qp_dims *dims, void *raw_memory); -// -acados_size_t ocp_qp_res_workspace_calculate_size(ocp_qp_dims *dims); -// -ocp_qp_res_ws *ocp_qp_res_workspace_assign(ocp_qp_dims *dims, void *raw_memory); -// -void ocp_qp_res_compute(ocp_qp_in *qp_in, ocp_qp_out *qp_out, ocp_qp_res *qp_res, ocp_qp_res_ws *res_ws); -// -void ocp_qp_res_compute_nrm_inf(ocp_qp_res *qp_res, double res[4]); - - -/* misc */ -// -void ocp_qp_stack_slacks_dims(ocp_qp_dims *in, ocp_qp_dims *out); -// -void ocp_qp_stack_slacks(ocp_qp_in *in, ocp_qp_in *out); -// -void ocp_qp_compute_t(ocp_qp_in *qp_in, ocp_qp_out *qp_out); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_QP_OCP_QP_COMMON_H_ diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_common_frontend.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_common_frontend.h deleted file mode 100644 index f65f602c15..0000000000 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_common_frontend.h +++ /dev/null @@ -1,118 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_OCP_QP_OCP_QP_COMMON_FRONTEND_H_ -#define ACADOS_OCP_QP_OCP_QP_COMMON_FRONTEND_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/ocp_qp/ocp_qp_common.h" - -typedef struct -{ - int N; - int *nx; - int *nu; - int *nb; - int *nc; - double **A; - double **B; - double **b; - double **Q; - double **S; - double **R; - double **q; - double **r; - int **idxb; - double **lb; - double **ub; - double **Cx; - double **Cu; - double **lc; - double **uc; -} colmaj_ocp_qp_in; - -typedef struct -{ - double **x; - double **u; - double **pi; - double **lam; -} colmaj_ocp_qp_out; - -typedef struct -{ - double **res_r; - double **res_q; - double **res_ls; - double **res_us; - double **res_b; - double **res_d_lb; - double **res_d_ub; - double **res_d_lg; - double **res_d_ug; - double **res_d_ls; - double **res_d_us; - double **res_m_lb; - double **res_m_ub; - double **res_m_lg; - double **res_m_ug; - double **res_m_ls; - double **res_m_us; - double res_nrm_inf[4]; -} colmaj_ocp_qp_res; - -// -acados_size_t colmaj_ocp_qp_in_calculate_size(ocp_qp_dims *dims); -// -char *assign_colmaj_ocp_qp_in(ocp_qp_dims *dims, colmaj_ocp_qp_in **qp_in, void *ptr); -// -acados_size_t colmaj_ocp_qp_out_calculate_size(ocp_qp_dims *dims); -// -char *assign_colmaj_ocp_qp_out(ocp_qp_dims *dims, colmaj_ocp_qp_out **qp_out, void *ptr); -// -acados_size_t colmaj_ocp_qp_res_calculate_size(ocp_qp_dims *dims); -// -char *assign_colmaj_ocp_qp_res(ocp_qp_dims *dims, colmaj_ocp_qp_res **qp_res, void *ptr); -// -void convert_colmaj_to_ocp_qp_in(colmaj_ocp_qp_in *cm_qp_in, ocp_qp_in *qp_in); -// -void convert_ocp_qp_out_to_colmaj(ocp_qp_out *qp_out, colmaj_ocp_qp_out *cm_qp_out); -// -void convert_ocp_qp_res_to_colmaj(ocp_qp_res *qp_res, colmaj_ocp_qp_res *cm_qp_res); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_QP_OCP_QP_COMMON_FRONTEND_H_ diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_full_condensing.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_full_condensing.h deleted file mode 100644 index d23e658b48..0000000000 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_full_condensing.h +++ /dev/null @@ -1,114 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_OCP_QP_OCP_QP_FULL_CONDENSING_H_ -#define ACADOS_OCP_QP_OCP_QP_FULL_CONDENSING_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// hpipm -#include "hpipm/include/hpipm_d_ocp_qp_red.h" -// acados -#include "acados/dense_qp/dense_qp_common.h" -#include "acados/ocp_qp/ocp_qp_common.h" -#include "acados/utils/types.h" - - - -typedef struct -{ - ocp_qp_dims *orig_dims; - ocp_qp_dims *red_dims; // dims of reduced qp - dense_qp_dims *fcond_dims; -} ocp_qp_full_condensing_dims; - - - -typedef struct ocp_qp_full_condensing_opts_ -{ - struct d_cond_qp_arg *hpipm_cond_opts; - struct d_ocp_qp_reduce_eq_dof_arg *hpipm_red_opts; -// dense_qp_dims *fcond_dims; // TODO(all): move to dims - int cond_hess; // 0 cond only rhs, 1 cond hess + rhs - int expand_dual_sol; // 0 primal sol only, 1 primal + dual sol - int ric_alg; - int mem_qp_in; // allocate qp_in in memory -} ocp_qp_full_condensing_opts; - - - -typedef struct ocp_qp_full_condensing_memory_ -{ - struct d_cond_qp_ws *hpipm_cond_work; - struct d_ocp_qp_reduce_eq_dof_ws *hpipm_red_work; - // in memory - dense_qp_in *fcond_qp_in; - dense_qp_out *fcond_qp_out; - ocp_qp_in *red_qp; // reduced qp - ocp_qp_out *red_sol; // reduced qp sol - // only pointer - ocp_qp_in *ptr_qp_in; - qp_info *qp_out_info; // info in fcond_qp_in - double time_qp_xcond; -} ocp_qp_full_condensing_memory; - - - -// -acados_size_t ocp_qp_full_condensing_opts_calculate_size(void *dims); -// -void *ocp_qp_full_condensing_opts_assign(void *dims, void *raw_memory); -// -void ocp_qp_full_condensing_opts_initialize_default(void *dims, void *opts_); -// -void ocp_qp_full_condensing_opts_update(void *dims, void *opts_); -// -void ocp_qp_full_condensing_opts_set(void *opts_, const char *field, void* value); -// -acados_size_t ocp_qp_full_condensing_memory_calculate_size(void *dims, void *opts_); -// -void *ocp_qp_full_condensing_memory_assign(void *dims, void *opts_, void *raw_memory); -// -acados_size_t ocp_qp_full_condensing_workspace_calculate_size(void *dims, void *opts_); -// -int ocp_qp_full_condensing(void *in, void *out, void *opts, void *mem, void *work); -// -int ocp_qp_full_expansion(void *in, void *out, void *opts, void *mem, void *work); -// -void ocp_qp_full_condensing_config_initialize_default(void *config_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_QP_OCP_QP_FULL_CONDENSING_H_ diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_hpipm.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_hpipm.h deleted file mode 100644 index 261606b842..0000000000 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_hpipm.h +++ /dev/null @@ -1,100 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_OCP_QP_OCP_QP_HPIPM_H_ -#define ACADOS_OCP_QP_OCP_QP_HPIPM_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// hpipm -#include "hpipm/include/hpipm_d_ocp_qp_ipm.h" -// acados -#include "acados/ocp_qp/ocp_qp_common.h" -#include "acados/utils/types.h" - - - -// struct of arguments to the solver -// TODO(roversch): why not make this a typedef of the underlying struct? -typedef struct ocp_qp_hpipm_opts_ -{ - struct d_ocp_qp_ipm_arg *hpipm_opts; -} ocp_qp_hpipm_opts; - - - -// TODO(roversch): why not make this a typedef of the underlying struct? -// struct of the solver memory -typedef struct ocp_qp_hpipm_memory_ -{ - struct d_ocp_qp_ipm_ws *hpipm_workspace; - double time_qp_solver_call; - int iter; - int status; - -} ocp_qp_hpipm_memory; - - - -// -acados_size_t ocp_qp_hpipm_opts_calculate_size(void *config, void *dims); -// -void *ocp_qp_hpipm_opts_assign(void *config, void *dims, void *raw_memory); -// -void ocp_qp_hpipm_opts_initialize_default(void *config, void *dims, void *opts_); -// -void ocp_qp_hpipm_opts_update(void *config, void *dims, void *opts_); -// -void ocp_qp_hpipm_opts_set(void *config_, void *opts_, const char *field, void *value); -// -acados_size_t ocp_qp_hpipm_memory_calculate_size(void *config, void *dims, void *opts_); -// -void *ocp_qp_hpipm_memory_assign(void *config, void *dims, void *opts_, void *raw_memory); -// -acados_size_t ocp_qp_hpipm_workspace_calculate_size(void *config, void *dims, void *opts_); -// -int ocp_qp_hpipm(void *config, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void ocp_qp_hpipm_memory_reset(void *config_, void *qp_in_, void *qp_out_, void *opts_, void *mem_, void *work_); -// -void ocp_qp_hpipm_eval_sens(void *config, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void ocp_qp_hpipm_config_initialize_default(void *config); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_QP_OCP_QP_HPIPM_H_ diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_hpmpc.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_hpmpc.h deleted file mode 100644 index 8db53a279d..0000000000 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_hpmpc.h +++ /dev/null @@ -1,127 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_OCP_QP_OCP_QP_HPMPC_H_ -#define ACADOS_OCP_QP_OCP_QP_HPMPC_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/ocp_qp/ocp_qp_common.h" -#include "acados/utils/types.h" - -typedef enum hpmpc_options_t_ { HPMPC_DEFAULT_ARGUMENTS } hpmpc_options_t; - -typedef struct ocp_qp_hpmpc_opts_ -{ - double tol; - int max_iter; - double mu0; - double alpha_min; - int warm_start; - int N2; // horizion length of the partially condensed problem - - // partial tightening - double sigma_mu; - int N; - int M; -} ocp_qp_hpmpc_opts; - -// struct of the solver memory -typedef struct ocp_qp_hpmpc_memory_ -{ - struct blasfeo_dvec *hpi; - double *stats; - - // workspace - void *hpmpc_work; // raw workspace - - // partial tightening-specific (init of extra variables) - struct blasfeo_dvec *lam0; - struct blasfeo_dvec *ux0; - struct blasfeo_dvec *pi0; - struct blasfeo_dvec *t0; - - // 2. workspace - struct blasfeo_dmat *hsL; - struct blasfeo_dmat *hsric_work_mat; - struct blasfeo_dmat sLxM; - struct blasfeo_dmat sPpM; - - struct blasfeo_dvec *hsQx; - struct blasfeo_dvec *hsqx; - struct blasfeo_dvec *hstinv; - struct blasfeo_dvec *hsrq; - struct blasfeo_dvec *hsdux; - - struct blasfeo_dvec *hsdlam; - struct blasfeo_dvec *hsdt; - struct blasfeo_dvec *hsdpi; - struct blasfeo_dvec *hslamt; - - struct blasfeo_dvec *hsPb; - - void *work_ric; - - int out_iter; - - double time_qp_solver_call; - int iter; - int status; - -} ocp_qp_hpmpc_memory; - -acados_size_t ocp_qp_hpmpc_opts_calculate_size(void *config_, ocp_qp_dims *dims); -// -void *ocp_qp_hpmpc_opts_assign(void *config_, ocp_qp_dims *dims, void *raw_memory); -// -void ocp_qp_hpmpc_opts_initialize_default(void *config_, ocp_qp_dims *dims, void *opts_); -// -void ocp_qp_hpmpc_opts_update(void *config_, ocp_qp_dims *dims, void *opts_); -// -acados_size_t ocp_qp_hpmpc_memory_calculate_size(void *config_, ocp_qp_dims *dims, void *opts_); -// -void *ocp_qp_hpmpc_memory_assign(void *config_, ocp_qp_dims *dims, void *opts_, void *raw_memory); -// -acados_size_t ocp_qp_hpmpc_workspace_calculate_size(void *config_, ocp_qp_dims *dims, void *opts_); -// -int ocp_qp_hpmpc(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void ocp_qp_hpmpc_eval_sens(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void ocp_qp_hpmpc_config_initialize_default(void *config_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_QP_OCP_QP_HPMPC_H_ diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_ooqp.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_ooqp.h deleted file mode 100644 index a535503f21..0000000000 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_ooqp.h +++ /dev/null @@ -1,144 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_OCP_QP_OCP_QP_OOQP_H_ -#define ACADOS_OCP_QP_OCP_QP_OOQP_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/ocp_qp/ocp_qp_common.h" -#include "acados/utils/types.h" - -enum ocp_qp_ooqp_termination_code -{ - SPARSE_SUCCESSFUL_TERMINATION = 0, - SPARSE_NOT_FINISHED, - SPARSE_MAX_ITS_EXCEEDED, - SPARSE_INFEASIBLE, - SPARSE_UNKNOWN -}; - -typedef struct ocp_qp_ooqp_opts_ -{ - int printLevel; - int useDiagonalWeights; // TODO(dimitris): implement option - int fixHessian; - int fixHessianSparsity; - int fixDynamics; - int fixDynamicsSparsity; - int fixInequalities; - int fixInequalitiesSparsity; -} ocp_qp_ooqp_opts; - -typedef struct ocp_qp_ooqp_workspace_ -{ - double *x; - double *gamma; - double *phi; - double *y; - double *z; - double *lambda; - double *pi; - double objectiveValue; - int *tmpInt; // temporary vector to sort indicies sparse matrices - double *tmpReal; // temporary vector to sort data of sparse matrices - // int ierr; -} ocp_qp_ooqp_workspace; - -typedef struct ocp_qp_ooqp_memory_ -{ - int firstRun; - double *c; - int nx; - int *irowQ; - int nnzQ; - int *jcolQ; - int *orderQ; - double *dQ; - double *xlow; - char *ixlow; - double *xupp; - char *ixupp; - int *irowA; - int nnzA; - int *jcolA; - int *orderA; - double *dA; - double *bA; - int my; - int *irowC; - int nnzC; - int *jcolC; - int *orderC; - double *dC; - double *clow; - int mz; - char *iclow; - double *cupp; - char *icupp; - int nnz; // max(nnzQ, nnzA, nnzC) - double time_qp_solver_call; - int iter; - int status; - -} ocp_qp_ooqp_memory; - -// -acados_size_t ocp_qp_ooqp_opts_calculate_size(void *config_, ocp_qp_dims *dims); -// -void *ocp_qp_ooqp_opts_assign(void *config_, ocp_qp_dims *dims, void *raw_memory); -// -void ocp_qp_ooqp_opts_initialize_default(void *config_, ocp_qp_dims *dims, void *opts_); -// -void ocp_qp_ooqp_opts_update(void *config_, ocp_qp_dims *dims, void *opts_); -// -acados_size_t ocp_qp_ooqp_memory_calculate_size(void *config_, ocp_qp_dims *dims, void *opts_); -// -void *ocp_qp_ooqp_memory_assign(void *config_, ocp_qp_dims *dims, void *opts_, void *raw_memory); -// -acados_size_t ocp_qp_ooqp_workspace_calculate_size(void *config_, ocp_qp_dims *dims, void *opts_); -// -int ocp_qp_ooqp(void *config_, ocp_qp_in *qp_in, ocp_qp_out *qp_out, void *opts_, void *memory_, - void *work_); -// -void ocp_qp_ooqp_destroy(void *mem_, void *work); -// -void ocp_qp_ooqp_eval_sens(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void ocp_qp_ooqp_config_initialize_default(void *config_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_QP_OCP_QP_OOQP_H_ diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_osqp.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_osqp.h deleted file mode 100644 index 51df1b1cd6..0000000000 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_osqp.h +++ /dev/null @@ -1,103 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_OCP_QP_OCP_QP_OSQP_H_ -#define ACADOS_OCP_QP_OCP_QP_OSQP_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// osqp -#include "osqp/include/types.h" - -// acados -#include "acados/ocp_qp/ocp_qp_common.h" -#include "acados/utils/types.h" - -typedef struct ocp_qp_osqp_opts_ -{ - OSQPSettings *osqp_opts; -} ocp_qp_osqp_opts; - - -typedef struct ocp_qp_osqp_memory_ -{ - c_int first_run; - - c_float *q; - c_float *l; - c_float *u; - - c_int P_nnzmax; - c_int *P_i; - c_int *P_p; - c_float *P_x; - - c_int A_nnzmax; - c_int *A_i; - c_int *A_p; - c_float *A_x; - - OSQPData *osqp_data; - OSQPWorkspace *osqp_work; - - double time_qp_solver_call; - int iter; - int status; - -} ocp_qp_osqp_memory; - -acados_size_t ocp_qp_osqp_opts_calculate_size(void *config, void *dims); -// -void *ocp_qp_osqp_opts_assign(void *config, void *dims, void *raw_memory); -// -void ocp_qp_osqp_opts_initialize_default(void *config, void *dims, void *opts_); -// -void ocp_qp_osqp_opts_update(void *config, void *dims, void *opts_); -// -acados_size_t ocp_qp_osqp_memory_calculate_size(void *config, void *dims, void *opts_); -// -void *ocp_qp_osqp_memory_assign(void *config, void *dims, void *opts_, void *raw_memory); -// -acados_size_t ocp_qp_osqp_workspace_calculate_size(void *config, void *dims, void *opts_); -// -int ocp_qp_osqp(void *config, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void ocp_qp_osqp_eval_sens(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void ocp_qp_osqp_config_initialize_default(void *config); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_QP_OCP_QP_OSQP_H_ diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_partial_condensing.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_partial_condensing.h deleted file mode 100644 index 844f6048fe..0000000000 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_partial_condensing.h +++ /dev/null @@ -1,120 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_OCP_QP_OCP_QP_PARTIAL_CONDENSING_H_ -#define ACADOS_OCP_QP_OCP_QP_PARTIAL_CONDENSING_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// hpipm -#include "hpipm/include/hpipm_d_ocp_qp_red.h" -// acados -#include "acados/ocp_qp/ocp_qp_common.h" - - - -typedef struct -{ - ocp_qp_dims *orig_dims; - ocp_qp_dims *red_dims; // dims of reduced qp - ocp_qp_dims *pcond_dims; - int *block_size; - int N2; - int N2_bkp; -} ocp_qp_partial_condensing_dims; - - - -typedef struct ocp_qp_partial_condensing_opts_ -{ - struct d_part_cond_qp_arg *hpipm_pcond_opts; - struct d_ocp_qp_reduce_eq_dof_arg *hpipm_red_opts; -// ocp_qp_dims *pcond_dims; // TODO(all): move to dims -// int *block_size; - int N2; - int N2_bkp; -// int expand_dual_sol; // 0 primal sol only, 1 primal + dual sol - int ric_alg; - int mem_qp_in; // allocate qp_in in memory -} ocp_qp_partial_condensing_opts; - - - -typedef struct ocp_qp_partial_condensing_memory_ -{ - struct d_part_cond_qp_ws *hpipm_pcond_work; - struct d_ocp_qp_reduce_eq_dof_ws *hpipm_red_work; - // in memory - ocp_qp_in *pcond_qp_in; - ocp_qp_out *pcond_qp_out; - ocp_qp_in *red_qp; // reduced qp - ocp_qp_out *red_sol; // reduced qp sol - // only pointer - ocp_qp_in *ptr_qp_in; - ocp_qp_in *ptr_pcond_qp_in; - qp_info *qp_out_info; // info in pcond_qp_in - double time_qp_xcond; -} ocp_qp_partial_condensing_memory; - - - -// -acados_size_t ocp_qp_partial_condensing_opts_calculate_size(void *dims); -// -void *ocp_qp_partial_condensing_opts_assign(void *dims, void *raw_memory); -// -void ocp_qp_partial_condensing_opts_initialize_default(void *dims, void *opts_); -// -void ocp_qp_partial_condensing_opts_update(void *dims, void *opts_); -// -void ocp_qp_partial_condensing_opts_set(void *opts_, const char *field, void* value); -// -acados_size_t ocp_qp_partial_condensing_memory_calculate_size(void *dims, void *opts_); -// -void *ocp_qp_partial_condensing_memory_assign(void *dims, void *opts, void *raw_memory); -// -acados_size_t ocp_qp_partial_condensing_workspace_calculate_size(void *dims, void *opts_); -// -int ocp_qp_partial_condensing(void *in, void *out, void *opts, void *mem, void *work); -// -int ocp_qp_partial_expansion(void *in, void *out, void *opts, void *mem, void *work); -// -void ocp_qp_partial_condensing_config_initialize_default(void *config_); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_QP_OCP_QP_PARTIAL_CONDENSING_H_ diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_qpdunes.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_qpdunes.h deleted file mode 100644 index 3b875caeb5..0000000000 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_qpdunes.h +++ /dev/null @@ -1,119 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_OCP_QP_OCP_QP_QPDUNES_H_ -#define ACADOS_OCP_QP_OCP_QP_QPDUNES_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "qpDUNES.h" - -#include "acados/ocp_qp/ocp_qp_common.h" -#include "acados/utils/types.h" - -typedef enum qpdunes_options_t_ { - QPDUNES_DEFAULT_ARGUMENTS, - QPDUNES_LINEAR_MPC, // TODO(dimitris): partly implemented - QPDUNES_NONLINEAR_MPC, // TODO(dimitris): not implemented yet - QPDUNES_ACADO_SETTINGS -} qpdunes_options_t; - -typedef enum { QPDUNES_WITH_QPOASES, QPDUNES_WITH_CLIPPING } qpdunes_stage_qp_solver_t; - -typedef struct ocp_qp_qpdunes_opts_ -{ - qpOptions_t options; - qpdunes_stage_qp_solver_t stageQpSolver; - int warmstart; // warmstart = 0: all multipliers set to zero, warmstart = 1: use previous mult. - bool isLinearMPC; -} ocp_qp_qpdunes_opts; - -typedef struct ocp_qp_qpdunes_memory_ -{ - int firstRun; - int nx; - int nu; - int nz; - int nDmax; // max(dims->ng) - qpData_t qpData; - double time_qp_solver_call; - int iter; - int status; - -} ocp_qp_qpdunes_memory; - -typedef struct ocp_qp_qpdunes_workspace_ -{ - double *H; - double *Q; - double *R; - double *S; - double *g; - double *ABt; - double *b; - double *Ct; - double *lc; - double *uc; - double *zLow; - double *zUpp; -} ocp_qp_qpdunes_workspace; - -// -acados_size_t ocp_qp_qpdunes_opts_calculate_size(void *config_, ocp_qp_dims *dims); -// -void *ocp_qp_qpdunes_opts_assign(void *config_, ocp_qp_dims *dims, void *raw_memory); -// -void ocp_qp_qpdunes_opts_initialize_default(void *config_, ocp_qp_dims *dims, void *opts_); -// -void ocp_qp_qpdunes_opts_update(void *config_, ocp_qp_dims *dims, void *opts_); -// -acados_size_t ocp_qp_qpdunes_memory_calculate_size(void *config_, ocp_qp_dims *dims, void *opts_); -// -void *ocp_qp_qpdunes_memory_assign(void *config_, ocp_qp_dims *dims, void *opts_, void *raw_memory); -// -acados_size_t ocp_qp_qpdunes_workspace_calculate_size(void *config_, ocp_qp_dims *dims, void *opts_); -// -int ocp_qp_qpdunes(void *config_, ocp_qp_in *qp_in, ocp_qp_out *qp_out, void *opts_, void *memory_, - void *work_); -// -void ocp_qp_qpdunes_free_memory(void *mem_); -// -void ocp_qp_qpdunes_eval_sens(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void ocp_qp_qpdunes_config_initialize_default(void *config_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_QP_OCP_QP_QPDUNES_H_ diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_xcond_solver.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_xcond_solver.h deleted file mode 100644 index a78bc65bb9..0000000000 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_xcond_solver.h +++ /dev/null @@ -1,150 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_OCP_QP_OCP_QP_PARTIAL_CONDENSING_SOLVER_H_ -#define ACADOS_OCP_QP_OCP_QP_PARTIAL_CONDENSING_SOLVER_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// acados -#include "acados/ocp_qp/ocp_qp_common.h" -#include "acados/utils/types.h" - - - -typedef struct -{ - ocp_qp_dims *orig_dims; - void *xcond_dims; -} ocp_qp_xcond_solver_dims; - - - -typedef struct ocp_qp_xcond_solver_opts_ -{ - void *xcond_opts; - void *qp_solver_opts; -} ocp_qp_xcond_solver_opts; - - - -typedef struct ocp_qp_xcond_solver_memory_ -{ - void *xcond_memory; - void *solver_memory; - void *xcond_qp_in; - void *xcond_qp_out; -} ocp_qp_xcond_solver_memory; - - - -typedef struct ocp_qp_xcond_solver_workspace_ -{ - void *xcond_work; - void *qp_solver_work; -} ocp_qp_xcond_solver_workspace; - - - -typedef struct -{ - acados_size_t (*dims_calculate_size)(void *config, int N); - ocp_qp_xcond_solver_dims *(*dims_assign)(void *config, int N, void *raw_memory); - void (*dims_set)(void *config_, ocp_qp_xcond_solver_dims *dims, int stage, const char *field, int* value); - void (*dims_get)(void *config_, ocp_qp_xcond_solver_dims *dims, int stage, const char *field, int* value); - acados_size_t (*opts_calculate_size)(void *config, ocp_qp_xcond_solver_dims *dims); - void *(*opts_assign)(void *config, ocp_qp_xcond_solver_dims *dims, void *raw_memory); - void (*opts_initialize_default)(void *config, ocp_qp_xcond_solver_dims *dims, void *opts); - void (*opts_update)(void *config, ocp_qp_xcond_solver_dims *dims, void *opts); - void (*opts_set)(void *config_, void *opts_, const char *field, void* value); - acados_size_t (*memory_calculate_size)(void *config, ocp_qp_xcond_solver_dims *dims, void *opts); - void *(*memory_assign)(void *config, ocp_qp_xcond_solver_dims *dims, void *opts, void *raw_memory); - void (*memory_get)(void *config_, void *mem_, const char *field, void* value); - void (*memory_reset)(void *config, ocp_qp_xcond_solver_dims *dims, ocp_qp_in *qp_in, ocp_qp_out *qp_out, void *opts, void *mem, void *work); - acados_size_t (*workspace_calculate_size)(void *config, ocp_qp_xcond_solver_dims *dims, void *opts); - int (*evaluate)(void *config, ocp_qp_xcond_solver_dims *dims, ocp_qp_in *qp_in, ocp_qp_out *qp_out, void *opts, void *mem, void *work); - void (*eval_sens)(void *config, ocp_qp_xcond_solver_dims *dims, ocp_qp_in *param_qp_in, ocp_qp_out *sens_qp_out, void *opts, void *mem, void *work); - qp_solver_config *qp_solver; // either ocp_qp_solver or dense_solver - ocp_qp_xcond_config *xcond; -} ocp_qp_xcond_solver_config; // pcond - partial condensing or fcond - full condensing - - - -/* config */ -// -acados_size_t ocp_qp_xcond_solver_config_calculate_size(); -// -ocp_qp_xcond_solver_config *ocp_qp_xcond_solver_config_assign(void *raw_memory); - -/* dims */ -// -acados_size_t ocp_qp_xcond_solver_dims_calculate_size(void *config, int N); -// -ocp_qp_xcond_solver_dims *ocp_qp_xcond_solver_dims_assign(void *config, int N, void *raw_memory); -// -void ocp_qp_xcond_solver_dims_set_(void *config, ocp_qp_xcond_solver_dims *dims, int stage, const char *field, int* value); - -/* opts */ -// -acados_size_t ocp_qp_xcond_solver_opts_calculate_size(void *config, ocp_qp_xcond_solver_dims *dims); -// -void *ocp_qp_xcond_solver_opts_assign(void *config, ocp_qp_xcond_solver_dims *dims, void *raw_memory); -// -void ocp_qp_xcond_solver_opts_initialize_default(void *config, ocp_qp_xcond_solver_dims *dims, void *opts_); -// -void ocp_qp_xcond_solver_opts_update(void *config, ocp_qp_xcond_solver_dims *dims, void *opts_); -// -void ocp_qp_xcond_solver_opts_set_(void *config_, void *opts_, const char *field, void* value); - -/* memory */ -// -acados_size_t ocp_qp_xcond_solver_memory_calculate_size(void *config, ocp_qp_xcond_solver_dims *dims, void *opts_); -// -void *ocp_qp_xcond_solver_memory_assign(void *config, ocp_qp_xcond_solver_dims *dims, void *opts_, void *raw_memory); - -/* workspace */ -// -acados_size_t ocp_qp_xcond_solver_workspace_calculate_size(void *config, ocp_qp_xcond_solver_dims *dims, void *opts_); - -/* config */ -// -int ocp_qp_xcond_solver(void *config, ocp_qp_xcond_solver_dims *dims, ocp_qp_in *qp_in, ocp_qp_out *qp_out, void *opts_, void *mem_, void *work_); - -// -void ocp_qp_xcond_solver_config_initialize_default(void *config_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_QP_OCP_QP_PARTIAL_CONDENSING_SOLVER_H_ diff --git a/third_party/acados/include/acados/sim/sim_collocation_utils.h b/third_party/acados/include/acados/sim/sim_collocation_utils.h deleted file mode 100644 index 045d165cbc..0000000000 --- a/third_party/acados/include/acados/sim/sim_collocation_utils.h +++ /dev/null @@ -1,97 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_SIM_SIM_COLLOCATION_UTILS_H_ -#define ACADOS_SIM_SIM_COLLOCATION_UTILS_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/utils/types.h" - - - -// enum Newton_type_collocation -// { -// exact = 0, -// simplified_in, -// simplified_inis -// }; - - - -// typedef struct -// { -// enum Newton_type_collocation type; -// double *eig; -// double *low_tria; -// bool single; -// bool freeze; - -// double *transf1; -// double *transf2; - -// double *transf1_T; -// double *transf2_T; -// } Newton_scheme; - - -typedef enum -{ - GAUSS_LEGENDRE, - GAUSS_RADAU_IIA, -} sim_collocation_type; - - -// -// acados_size_t gauss_legendre_nodes_work_calculate_size(int ns); -// -// void gauss_legendre_nodes(int ns, double *nodes, void *raw_memory); -// -// acados_size_t gauss_simplified_work_calculate_size(int ns); -// // -// void gauss_simplified(int ns, Newton_scheme *scheme, void *work); -// -acados_size_t butcher_tableau_work_calculate_size(int ns); -// -// void calculate_butcher_tableau_from_nodes(int ns, double *nodes, double *b, double *A, void *work); -// -void calculate_butcher_tableau(int ns, sim_collocation_type collocation_type, double *c_vec, - double *b_vec, double *A_mat, void *work); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_SIM_SIM_COLLOCATION_UTILS_H_ diff --git a/third_party/acados/include/acados/sim/sim_common.h b/third_party/acados/include/acados/sim/sim_common.h deleted file mode 100644 index c4bbd6ed2b..0000000000 --- a/third_party/acados/include/acados/sim/sim_common.h +++ /dev/null @@ -1,221 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_SIM_SIM_COMMON_H_ -#define ACADOS_SIM_SIM_COMMON_H_ - -#include - -#include "acados/sim/sim_collocation_utils.h" -#include "acados/utils/timing.h" -#include "acados/utils/types.h" - -#include "acados/utils/external_function_generic.h" - -// maximum number of integration stages -#define NS_MAX 15 - - - -typedef enum -{ - // ERK and LIFTED_ERK - EXPL_ODE_FUN, - EXPL_ODE_HES, // wrt x and u ??? - EXPL_VDE_FOR, - EXPL_VDE_ADJ, - // IRK - IMPL_ODE_FUN, - IMPL_ODE_FUN_JAC_X_XDOT, - IMPL_ODE_JAC_X_XDOT_U, - IMPL_ODE_FUN_JAC_X_XDOT_U, - IMPL_ODE_HESS, - // gnsf - PHI_FUN, - PHI_FUN_JAC_Y, - PHI_JAC_Y_UHAT, - LO_FUN, - GET_GNSF_MATRICES -} sim_function_t; - - - -typedef struct -{ - void *dims; - - double *x; // x[NX] - initial state value for simulation - double *u; // u[NU] - control - constant over simulation time - - double *S_forw; // forward seed [Sx, Su] - double *S_adj; // backward seed - - bool identity_seed; // indicating if S_forw = [eye(nx), zeros(nx x nu)] - - void *model; - - double T; // simulation time - -} sim_in; - - - -typedef struct -{ - double CPUtime; // in seconds - double LAtime; // in seconds - double ADtime; // in seconds - -} sim_info; - - - -typedef struct -{ - double *xn; // xn[NX] - double *S_forw; // S_forw[NX*(NX+NU)] - double *S_adj; // - double *S_hess; // - - double *zn; // z - algebraic variables - reported at start of simulation interval - double *S_algebraic; // sensitivities of reported value of algebraic variables w.r.t. - // initial stat & control (x_n,u) - - double *grad; // gradient correction - - sim_info *info; - -} sim_out; - - - -typedef struct -{ - int ns; // number of integration stages - - int num_steps; - int num_forw_sens; - - int tableau_size; // check that is consistent with ns - // only update when butcher tableau is changed - // kind of private -> no setter! - double *A_mat; - double *c_vec; - double *b_vec; - - bool sens_forw; - bool sens_adj; - bool sens_hess; - - bool output_z; // 1 -- if zn should be computed - bool sens_algebraic; // 1 -- if S_algebraic should be computed - bool exact_z_output; // 1 -- if z, S_algebraic should be computed exactly, extra Newton iterations - sim_collocation_type collocation_type; - - // for explicit integrators: newton_iter == 0 && scheme == NULL - // && jac_reuse=false - int newton_iter; - bool jac_reuse; - // Newton_scheme *scheme; - - double newton_tol; // optinally used in implicit integrators - - // workspace - void *work; - -} sim_opts; - - - -typedef struct -{ - int (*evaluate)(void *config_, sim_in *in, sim_out *out, void *opts, void *mem, void *work); - int (*precompute)(void *config_, sim_in *in, sim_out *out, void *opts, void *mem, void *work); - // opts - acados_size_t (*opts_calculate_size)(void *config_, void *dims); - void *(*opts_assign)(void *config_, void *dims, void *raw_memory); - void (*opts_initialize_default)(void *config_, void *dims, void *opts); - void (*opts_update)(void *config_, void *dims, void *opts); - void (*opts_set)(void *config_, void *opts_, const char *field, void *value); - void (*opts_get)(void *config_, void *opts_, const char *field, void *value); - // mem - acados_size_t (*memory_calculate_size)(void *config, void *dims, void *opts); - void *(*memory_assign)(void *config, void *dims, void *opts, void *raw_memory); - int (*memory_set)(void *config, void *dims, void *mem, const char *field, void *value); - int (*memory_set_to_zero)(void *config, void *dims, void *opts, void *mem, const char *field); - void (*memory_get)(void *config, void *dims, void *mem, const char *field, void *value); - // work - acados_size_t (*workspace_calculate_size)(void *config, void *dims, void *opts); - // model - acados_size_t (*model_calculate_size)(void *config, void *dims); - void *(*model_assign)(void *config, void *dims, void *raw_memory); - int (*model_set)(void *model, const char *field, void *value); - // config - void (*config_initialize_default)(void *config); - // dims - acados_size_t (*dims_calculate_size)(); - void *(*dims_assign)(void *config, void *raw_memory); - void (*dims_set)(void *config, void *dims, const char *field, const int *value); - void (*dims_get)(void *config, void *dims, const char *field, int *value); - -} sim_config; - - - -/* config */ -// -acados_size_t sim_config_calculate_size(); -// -sim_config *sim_config_assign(void *raw_memory); - -/* in */ -// -acados_size_t sim_in_calculate_size(void *config, void *dims); -// -sim_in *sim_in_assign(void *config, void *dims, void *raw_memory); -// -int sim_in_set_(void *config_, void *dims_, sim_in *in, const char *field, void *value); - -/* out */ -// -acados_size_t sim_out_calculate_size(void *config, void *dims); -// -sim_out *sim_out_assign(void *config, void *dims, void *raw_memory); -// -int sim_out_get_(void *config, void *dims, sim_out *out, const char *field, void *value); - -/* opts */ -// -void sim_opts_set_(sim_opts *opts, const char *field, void *value); -// -void sim_opts_get_(sim_config *config, sim_opts *opts, const char *field, void *value); - -#endif // ACADOS_SIM_SIM_COMMON_H_ diff --git a/third_party/acados/include/acados/sim/sim_erk_integrator.h b/third_party/acados/include/acados/sim/sim_erk_integrator.h deleted file mode 100644 index fd46cb4d99..0000000000 --- a/third_party/acados/include/acados/sim/sim_erk_integrator.h +++ /dev/null @@ -1,140 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_SIM_SIM_ERK_INTEGRATOR_H_ -#define ACADOS_SIM_SIM_ERK_INTEGRATOR_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/sim/sim_common.h" -#include "acados/utils/types.h" - - - -typedef struct -{ - int nx; - int nu; - int nz; -} sim_erk_dims; - - - -typedef struct -{ - /* external functions */ - // explicit ode - external_function_generic *expl_ode_fun; - // hessian explicit ode - external_function_generic *expl_ode_hes; - // forward explicit vde - external_function_generic *expl_vde_for; - // adjoint explicit vde - external_function_generic *expl_vde_adj; - -} erk_model; - - - -typedef struct -{ - // memory - double time_sim; - double time_ad; - double time_la; - - // workspace structs -} sim_erk_memory; - - - -typedef struct -{ - // workspace mem - double *rhs_forw_in; // x + S + p - - double *K_traj; // (stages*nX) or (steps*stages*nX) for adj - double *out_forw_traj; // S or (steps+1)*nX for adj - - double *rhs_adj_in; - double *out_adj_tmp; - double *adj_traj; - -} sim_erk_workspace; - - - -// dims -acados_size_t sim_erk_dims_calculate_size(); -void *sim_erk_dims_assign(void *config_, void *raw_memory); -void sim_erk_dims_set(void *config_, void *dims_, const char *field, const int* value); -void sim_erk_dims_get(void *config_, void *dims_, const char *field, int* value); - -// model -acados_size_t sim_erk_model_calculate_size(void *config, void *dims); -void *sim_erk_model_assign(void *config, void *dims, void *raw_memory); -int sim_erk_model_set(void *model, const char *field, void *value); - -// opts -acados_size_t sim_erk_opts_calculate_size(void *config, void *dims); -// -void sim_erk_opts_update(void *config_, void *dims, void *opts_); -// -void *sim_erk_opts_assign(void *config, void *dims, void *raw_memory); -// -void sim_erk_opts_initialize_default(void *config, void *dims, void *opts_); -// -void sim_erk_opts_set(void *config_, void *opts_, const char *field, void *value); - - -// memory -acados_size_t sim_erk_memory_calculate_size(void *config, void *dims, void *opts_); -// -void *sim_erk_memory_assign(void *config, void *dims, void *opts_, void *raw_memory); -// -int sim_erk_memory_set(void *config_, void *dims_, void *mem_, const char *field, void *value); - - -// workspace -acados_size_t sim_erk_workspace_calculate_size(void *config, void *dims, void *opts_); - -// -int sim_erk(void *config, sim_in *in, sim_out *out, void *opts_, void *mem_, void *work_); -// -void sim_erk_config_initialize_default(void *config); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_SIM_SIM_ERK_INTEGRATOR_H_ diff --git a/third_party/acados/include/acados/sim/sim_gnsf.h b/third_party/acados/include/acados/sim/sim_gnsf.h deleted file mode 100644 index 404532a732..0000000000 --- a/third_party/acados/include/acados/sim/sim_gnsf.h +++ /dev/null @@ -1,364 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_SIM_SIM_GNSF_H_ -#define ACADOS_SIM_SIM_GNSF_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include - -#include "acados/utils/timing.h" -#include "acados/utils/types.h" -#include "acados/sim/sim_common.h" - -#include "blasfeo/include/blasfeo_common.h" -// #include "blasfeo/include/blasfeo_d_aux.h" -// #include "blasfeo/include/blasfeo_d_aux_ext_dep.h" -// #include "blasfeo/include/blasfeo_d_blas.h" -// #include "blasfeo/include/blasfeo_d_kernel.h" -// #include "blasfeo/include/blasfeo_i_aux_ext_dep.h" -// #include "blasfeo/include/blasfeo_target.h" - -/* -GNSF - Generalized Nonlinear Static Feedback Model -has the following form -https://github.com/acados/acados/files/3359595/gnsf_structure_blo.pdf - -Details on the algorithm can be found in master thesis of Jonathan Frey, -which presents a slightly different format without the terms B_LO, c_LO. -https://github.com/acados/acados/files/2318322/gnsf_structure.pdf -https://cdn.syscop.de/publications/Frey2018.pdf -https://cdn.syscop.de/publications/Frey2019.pdf -*/ - -typedef struct -{ - int nx; // total number of differential states - int nu; // total number of inputs - int nz; // total number of algebraic states - int nx1; // number of differential states in NSF part - int nz1; // number of algebraic states in NSF part - int n_out; // output dimension of phi - int ny; // dimension of first input of phi - int nuhat; // dimension of second input of phi - -} sim_gnsf_dims; - - - -typedef struct -{ - /* external functions */ - // phi: nonlinearity function - external_function_generic *phi_fun; - external_function_generic *phi_fun_jac_y; - external_function_generic *phi_jac_y_uhat; - - // f_lo: linear output function - external_function_generic *f_lo_fun_jac_x1_x1dot_u_z; - - // to import model matrices - external_function_generic *get_gnsf_matrices; - - // flag indicating, if model defining matrices are imported via external (casadi) function, - // [default]: true -> auto; - bool auto_import_gnsf; - - // booleans from structure detection - bool nontrivial_f_LO; // indicates if f_LO is constant zero function - bool fully_linear; // indicates if model is fully linear LOS - - /* model defining matrices */ - // TODO: add setters to set manually - double *A; - double *B; - double *C; - double *E; - - double *L_x; - double *L_xdot; - double *L_z; - double *L_u; - - double *A_LO; - double *B_LO; - double *E_LO; - - /* constant vector */ - double *c; - double *c_LO; - - // permutation vector - to have GNSF order of x, z within sim_gnsf only - int *ipiv_x; - int *ipiv_z; - - double *ipiv_x_double; - double *ipiv_z_double; - -} gnsf_model; - - - -// pre_workspace - workspace used in the precomputation phase -typedef struct -{ - struct blasfeo_dmat E11; - struct blasfeo_dmat E12; - struct blasfeo_dmat E21; - struct blasfeo_dmat E22; - - struct blasfeo_dmat A1; - struct blasfeo_dmat A2; - struct blasfeo_dmat B1; - struct blasfeo_dmat B2; - struct blasfeo_dmat C1; - struct blasfeo_dmat C2; - - struct blasfeo_dmat AA1; - struct blasfeo_dmat AA2; - struct blasfeo_dmat BB1; - struct blasfeo_dmat BB2; - struct blasfeo_dmat CC1; - struct blasfeo_dmat CC2; - struct blasfeo_dmat DD1; - struct blasfeo_dmat DD2; - struct blasfeo_dmat EE1; - struct blasfeo_dmat EE2; - - struct blasfeo_dmat QQ1; - - struct blasfeo_dmat LLZ; - struct blasfeo_dmat LLx; - struct blasfeo_dmat LLK; - - int *ipivEE1; // index of pivot vector - int *ipivEE2; - int *ipivQQ1; - - // for algebraic sensitivity propagation - struct blasfeo_dmat Q1; - - // for constant term in NSF - struct blasfeo_dvec cc1; - struct blasfeo_dvec cc2; - -} gnsf_pre_workspace; - - - -// workspace -typedef struct -{ - double *Z_work; // used to perform computations to get out->zn - - int *ipiv; // index of pivot vector - - struct blasfeo_dvec *vv_traj; - struct blasfeo_dvec *yy_traj; - struct blasfeo_dmat *f_LO_jac_traj; - - struct blasfeo_dvec K2_val; - struct blasfeo_dvec x0_traj; - struct blasfeo_dvec res_val; - struct blasfeo_dvec u0; - struct blasfeo_dvec lambda; - struct blasfeo_dvec lambda_old; - - struct blasfeo_dvec yyu; - struct blasfeo_dvec yyss; - - struct blasfeo_dvec K1_val; - struct blasfeo_dvec f_LO_val; - struct blasfeo_dvec x1_stage_val; - struct blasfeo_dvec Z1_val; - - struct blasfeo_dvec K1u; - struct blasfeo_dvec Zu; - struct blasfeo_dvec ALOtimesx02; - struct blasfeo_dvec BLOtimesu0; - - struct blasfeo_dvec uhat; - - struct blasfeo_dmat J_r_vv; - struct blasfeo_dmat J_r_x1u; - - struct blasfeo_dmat dK1_dx1; - struct blasfeo_dmat dK1_du; - struct blasfeo_dmat dZ_dx1; - struct blasfeo_dmat dZ_du; - struct blasfeo_dmat J_G2_K1; - - struct blasfeo_dmat dK2_dx1; - struct blasfeo_dmat dK2_dvv; - struct blasfeo_dmat dxf_dwn; - struct blasfeo_dmat S_forw_new; - struct blasfeo_dmat S_algebraic_aux; - - struct blasfeo_dmat dPsi_dvv; - struct blasfeo_dmat dPsi_dx; - struct blasfeo_dmat dPsi_du; - - struct blasfeo_dmat dPHI_dyuhat; - struct blasfeo_dvec z0; - - // memory only available if (opts->sens_algebraic) - // struct blasfeo_dvec y_one_stage; - // struct blasfeo_dvec x0dot_1; - // struct blasfeo_dmat dz10_dx1u; // (nz1) * (nx1+nu); - // struct blasfeo_dmat dr0_dvv0; // (n_out * n_out) - // struct blasfeo_dmat f_LO_jac0; // (nx2+nz2) * (2*nx1 + nz1 + nu) - // struct blasfeo_dmat sens_z2_rhs; // (nx2 + nz2) * (nx1 + nu) - // int *ipiv_vv0; - -} gnsf_workspace; - - - -// memory -typedef struct -{ - bool first_call; - - // simulation time for one step - double dt; - - // (scaled) butcher table - double *A_dt; - double *b_dt; - double *c_butcher; - - // value used to initialize integration variables - corresponding to value of phi - double *phi_guess; // n_out - - struct blasfeo_dmat S_forw; - struct blasfeo_dmat S_algebraic; - - // precomputed matrices - struct blasfeo_dmat KKv; - struct blasfeo_dmat KKx; - struct blasfeo_dmat KKu; - - struct blasfeo_dmat YYv; - struct blasfeo_dmat YYx; - struct blasfeo_dmat YYu; - - struct blasfeo_dmat ZZv; - struct blasfeo_dmat ZZx; - struct blasfeo_dmat ZZu; - - struct blasfeo_dmat ALO; - struct blasfeo_dmat BLO; - struct blasfeo_dmat M2_LU; - int *ipivM2; - - struct blasfeo_dmat dK2_dx2; - struct blasfeo_dmat dK2_du; - struct blasfeo_dmat dx2f_dx2u; - - struct blasfeo_dmat Lu; - - // precomputed vectors for constant term in NSF - struct blasfeo_dvec KK0; - struct blasfeo_dvec YY0; - struct blasfeo_dvec ZZ0; - - // for algebraic sensitivities only; - // struct blasfeo_dmat *Z0x; - // struct blasfeo_dmat *Z0u; - // struct blasfeo_dmat *Z0v; - - // struct blasfeo_dmat *Y0x; - // struct blasfeo_dmat *Y0u; - // struct blasfeo_dmat *Y0v; - - // struct blasfeo_dmat *K0x; - // struct blasfeo_dmat *K0u; - // struct blasfeo_dmat *K0v; - - // struct blasfeo_dmat *ELO_LU; - // int *ipiv_ELO; - // struct blasfeo_dmat *ELO_inv_ALO; - - // struct blasfeo_dmat *Lx; - // struct blasfeo_dmat *Lxdot; - // struct blasfeo_dmat *Lz; - - double time_sim; - double time_ad; - double time_la; - -} sim_gnsf_memory; - - - -// gnsf dims -acados_size_t sim_gnsf_dims_calculate_size(); -void *sim_gnsf_dims_assign(void *config_, void *raw_memory); - -// get & set functions -void sim_gnsf_dims_set(void *config_, void *dims_, const char *field, const int *value); -void sim_gnsf_dims_get(void *config_, void *dims_, const char *field, int* value); - -// opts -acados_size_t sim_gnsf_opts_calculate_size(void *config, void *dims); -void *sim_gnsf_opts_assign(void *config, void *dims, void *raw_memory); -void sim_gnsf_opts_initialize_default(void *config, void *dims, void *opts_); -void sim_gnsf_opts_update(void *config_, void *dims, void *opts_); -void sim_gnsf_opts_set(void *config_, void *opts_, const char *field, void *value); - -// model -acados_size_t sim_gnsf_model_calculate_size(void *config, void *dims_); -void *sim_gnsf_model_assign(void *config, void *dims_, void *raw_memory); -int sim_gnsf_model_set(void *model_, const char *field, void *value); - -// precomputation -int sim_gnsf_precompute(void *config_, sim_in *in, sim_out *out, void *opts_, void *mem_, - void *work_); - -// workspace & memory -acados_size_t sim_gnsf_workspace_calculate_size(void *config, void *dims_, void *args); -acados_size_t sim_gnsf_memory_calculate_size(void *config, void *dims_, void *opts_); -void *sim_gnsf_memory_assign(void *config, void *dims_, void *opts_, void *raw_memory); - -// interface -void sim_gnsf_config_initialize_default(void *config_); - -// integrator -int sim_gnsf(void *config, sim_in *in, sim_out *out, void *opts, void *mem_, void *work_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_SIM_SIM_GNSF_H_ diff --git a/third_party/acados/include/acados/sim/sim_irk_integrator.h b/third_party/acados/include/acados/sim/sim_irk_integrator.h deleted file mode 100644 index 5090aa0bb5..0000000000 --- a/third_party/acados/include/acados/sim/sim_irk_integrator.h +++ /dev/null @@ -1,183 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_SIM_SIM_IRK_INTEGRATOR_H_ -#define ACADOS_SIM_SIM_IRK_INTEGRATOR_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/sim/sim_common.h" -#include "acados/utils/types.h" - -#include "blasfeo/include/blasfeo_common.h" - -typedef struct -{ - int nx; - int nu; - int nz; - -} sim_irk_dims; - - - -typedef struct -{ - /* external functions */ - // implicit fun - can either be fully implicit ode or dae - // - i.e. dae has z as additional last argument & nz > 0 - external_function_generic *impl_ode_fun; - // implicit ode & jac_x & jax_xdot & jac_z - external_function_generic *impl_ode_fun_jac_x_xdot_z; - // jax_x & jac_xdot & jac_u & jac_z of implicit ode - external_function_generic *impl_ode_jac_x_xdot_u_z; - // hessian of implicit ode: - external_function_generic *impl_ode_hess; -} irk_model; - - - -typedef struct -{ - struct blasfeo_dvec *rG; // residuals of G (nx*ns) - struct blasfeo_dvec *K; // internal K variables ((nx+nz)*ns) - struct blasfeo_dvec *xt; // temporary x - struct blasfeo_dvec *xn; // x at each integration step - struct blasfeo_dvec xtdot; // temporary xdot - - struct blasfeo_dvec *lambda; // adjoint sensitivities (nx + nu) - struct blasfeo_dvec *lambdaK; // auxiliary variable ((nx+nz)*ns) for adjoint propagation - - struct blasfeo_dmat df_dx; // temporary Jacobian of ode w.r.t x (nx+nz, nx) - struct blasfeo_dmat df_dxdot; // temporary Jacobian of ode w.r.t xdot (nx+nz, nx) - struct blasfeo_dmat df_du; // temporary Jacobian of ode w.r.t u (nx+nz, nu) - struct blasfeo_dmat df_dz; // temporary Jacobian of ode w.r.t z (nx+nz, nu) - - /* NOTE: the memory allocation corresponding to the following fields is CONDITIONAL */ - - // only allocated if (opts->sens_algebraic || opts->output_z) - int *ipiv_one_stage; // index of pivot vector (nx + nz) - double *Z_work; // used to perform computations to get out->zn (ns) - - // df_dxdotz, dk0_dxu, only allocated if (opts->sens_algebraic && opts->exact_z_output) - // used for algebraic sensitivity generation - struct blasfeo_dmat df_dxdotz; // temporary Jacobian of ode w.r.t. xdot,z (nx+nz, nx+nz); - struct blasfeo_dmat dk0_dxu; // intermediate result, (nx+nz, nx+nu) - - // dK_dxu: if (!opts->sens_hess) - single blasfeo_dmat that is reused - // if ( opts->sens_hess) - array of (num_steps) blasfeo_dmat - // to store intermediate results - struct blasfeo_dmat *dK_dxu; // jacobian of (K,Z) over x and u ((nx+nz)*ns, nx+nu); - - // S_forw: if (!opts->sens_hess) - single blasfeo_dmat that is reused - // if ( opts->sens_hess) - array of (num_steps + 1) blasfeo_dmat - // to store intermediate results - struct blasfeo_dmat *S_forw; // forward sensitivities (nx, nx+nu) - - // dG_dxu: if (!opts->sens_hess) - single blasfeo_dmat that is reused - // if ( opts->sens_hess) - array of blasfeo_dmat to store intermediate results - struct blasfeo_dmat *dG_dxu; // jacobian of G over x and u ((nx+nz)*ns, nx+nu) - - // dG_dK: if (!opts->sens_hess) - single blasfeo_dmat that is reused - // if ( opts->sens_hess) - array of blasfeo_dmat to store intermediate results - struct blasfeo_dmat *dG_dK; // jacobian of G over K ((nx+nz)*ns, (nx+nz)*ns) - - // ipiv: index of pivot vector - // if (!opts->sens_hess) - array (ns * (nx + nz)) that is reused - // if ( opts->sens_hess) - array (ns * (nx + nz)) * num_steps, to store all - // pivot vectors for dG_dxu - int *ipiv; // index of pivot vector - - // xn_traj, K_traj only available if( opts->sens_adj || opts->sens_hess ) - struct blasfeo_dvec *xn_traj; // xn trajectory - struct blasfeo_dvec *K_traj; // K trajectory - - /* the following variables are only available if (opts->sens_hess) */ - // For Hessian propagation - struct blasfeo_dmat Hess; // temporary Hessian (nx + nu, nx + nu) - // output of impl_ode_hess - struct blasfeo_dmat f_hess; // size: (nx + nu, nx + nu) - struct blasfeo_dmat dxkzu_dw0; // size (2*nx + nu + nz) x (nx + nu) - struct blasfeo_dmat tmp_dxkzu_dw0; // size (2*nx + nu + nz) x (nx + nu) - -} sim_irk_workspace; - - -typedef struct -{ - double *xdot; // xdot[NX] - initialization for state derivatives k within the integrator - double *z; // z[NZ] - initialization for algebraic variables z - - double time_sim; - double time_ad; - double time_la; -} sim_irk_memory; - - -// get & set functions -void sim_irk_dims_set(void *config_, void *dims_, const char *field, const int *value); -void sim_irk_dims_get(void *config_, void *dims_, const char *field, int* value); - -// dims -acados_size_t sim_irk_dims_calculate_size(); -void *sim_irk_dims_assign(void *config_, void *raw_memory); - -// model -acados_size_t sim_irk_model_calculate_size(void *config, void *dims); -void *sim_irk_model_assign(void *config, void *dims, void *raw_memory); -int sim_irk_model_set(void *model, const char *field, void *value); - -// opts -acados_size_t sim_irk_opts_calculate_size(void *config, void *dims); -void *sim_irk_opts_assign(void *config, void *dims, void *raw_memory); -void sim_irk_opts_initialize_default(void *config, void *dims, void *opts_); -void sim_irk_opts_update(void *config_, void *dims, void *opts_); -void sim_irk_opts_set(void *config_, void *opts_, const char *field, void *value); - -// memory -acados_size_t sim_irk_memory_calculate_size(void *config, void *dims, void *opts_); -void *sim_irk_memory_assign(void *config, void *dims, void *opts_, void *raw_memory); -int sim_irk_memory_set(void *config_, void *dims_, void *mem_, const char *field, void *value); - -// workspace -acados_size_t sim_irk_workspace_calculate_size(void *config, void *dims, void *opts_); -void sim_irk_config_initialize_default(void *config); - -// main -int sim_irk(void *config, sim_in *in, sim_out *out, void *opts_, void *mem_, void *work_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_SIM_SIM_IRK_INTEGRATOR_H_ diff --git a/third_party/acados/include/acados/sim/sim_lifted_irk_integrator.h b/third_party/acados/include/acados/sim/sim_lifted_irk_integrator.h deleted file mode 100644 index e60bb80ebf..0000000000 --- a/third_party/acados/include/acados/sim/sim_lifted_irk_integrator.h +++ /dev/null @@ -1,157 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_SIM_SIM_LIFTED_IRK_INTEGRATOR_H_ -#define ACADOS_SIM_SIM_LIFTED_IRK_INTEGRATOR_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/sim/sim_common.h" -#include "acados/utils/types.h" - -typedef struct -{ - int nx; - int nu; - int nz; -} sim_lifted_irk_dims; - - - -typedef struct -{ - /* external functions */ - // implicit ode - external_function_generic *impl_ode_fun; - // implicit ode & jax_x & jac_xdot & jac_u implicit ode - external_function_generic *impl_ode_fun_jac_x_xdot_u; - -} lifted_irk_model; - - - -typedef struct -{ - - struct blasfeo_dmat *J_temp_x; // temporary Jacobian of ode w.r.t x (nx, nx) - struct blasfeo_dmat *J_temp_xdot; // temporary Jacobian of ode w.r.t xdot (nx, nx) - struct blasfeo_dmat *J_temp_u; // temporary Jacobian of ode w.r.t u (nx, nu) - - struct blasfeo_dvec *rG; // residuals of G (nx*ns) - struct blasfeo_dvec *xt; // temporary x - struct blasfeo_dvec *xn; // x at each integration step (for evaluations) - struct blasfeo_dvec *xn_out; // x at each integration step (output) - struct blasfeo_dvec *dxn; // dx at each integration step - struct blasfeo_dvec *w; // stacked x and u - - int *ipiv; // index of pivot vector - -} sim_lifted_irk_workspace; - - - -typedef struct -{ - // memory for lifted integrators - struct blasfeo_dmat *S_forw; // forward sensitivities - struct blasfeo_dmat *JGK; // jacobian of G over K (nx*ns, nx*ns) - struct blasfeo_dmat *JGf; // jacobian of G over x and u (nx*ns, nx+nu); - struct blasfeo_dmat *JKf; // jacobian of K over x and u (nx*ns, nx+nu); - - struct blasfeo_dvec *K; // internal variables (nx*ns) - struct blasfeo_dvec *x; // states (nx) -- for expansion step - struct blasfeo_dvec *u; // controls (nu) -- for expansion step - - int update_sens; - // int init_K; - - double time_sim; - double time_ad; - double time_la; - -} sim_lifted_irk_memory; - - - -/* dims */ -void sim_lifted_irk_dims_set(void *config_, void *dims_, const char *field, const int *value); -void sim_lifted_irk_dims_get(void *config_, void *dims_, const char *field, int* value); - -acados_size_t sim_lifted_irk_dims_calculate_size(); -// -void *sim_lifted_irk_dims_assign(void* config_, void *raw_memory); - -/* model */ -// -acados_size_t sim_lifted_irk_model_calculate_size(void *config, void *dims); -// -void *sim_lifted_irk_model_assign(void *config, void *dims, void *raw_memory); -// -int sim_lifted_irk_model_set(void *model_, const char *field, void *value); - -/* opts */ -// -acados_size_t sim_lifted_irk_opts_calculate_size(void *config, void *dims); -// -void *sim_lifted_irk_opts_assign(void *config, void *dims, void *raw_memory); -// -void sim_lifted_irk_opts_initialize_default(void *config, void *dims, void *opts_); -// -void sim_lifted_irk_opts_update(void *config_, void *dims, void *opts_); -// -void sim_lifted_irk_opts_set(void *config_, void *opts_, const char *field, void *value); - -/* memory */ -// -acados_size_t sim_lifted_irk_memory_calculate_size(void *config, void *dims, void *opts_); -// -void *sim_lifted_irk_memory_assign(void *config, void *dims, void *opts_, void *raw_memory); - -/* workspace */ -// -acados_size_t sim_lifted_irk_workspace_calculate_size(void *config, void *dims, void *opts_); -// -void sim_lifted_irk_config_initialize_default(void *config); - -/* solver */ -// -int sim_lifted_irk(void *config, sim_in *in, sim_out *out, void *opts_, - void *mem_, void *work_); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_SIM_SIM_LIFTED_IRK_INTEGRATOR_H_ diff --git a/third_party/acados/include/acados/utils/external_function_generic.h b/third_party/acados/include/acados/utils/external_function_generic.h deleted file mode 100644 index 1e68dc155d..0000000000 --- a/third_party/acados/include/acados/utils/external_function_generic.h +++ /dev/null @@ -1,242 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_UTILS_EXTERNAL_FUNCTION_GENERIC_H_ -#define ACADOS_UTILS_EXTERNAL_FUNCTION_GENERIC_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/utils/types.h" - -/************************************************ - * generic external function - ************************************************/ - -// type of arguments -typedef enum { - COLMAJ, - BLASFEO_DMAT, - BLASFEO_DVEC, - COLMAJ_ARGS, - BLASFEO_DMAT_ARGS, - BLASFEO_DVEC_ARGS, - IGNORE_ARGUMENT -} ext_fun_arg_t; - -struct colmaj_args -{ - double *A; - int lda; -}; - -struct blasfeo_dmat_args -{ - struct blasfeo_dmat *A; - int ai; - int aj; -}; - -struct blasfeo_dvec_args -{ - struct blasfeo_dvec *x; - int xi; -}; - -// prototype of an external function -typedef struct -{ - // public members (have to be before private ones) - void (*evaluate)(void *, ext_fun_arg_t *, void **, ext_fun_arg_t *, void **); - // private members - // ..... -} external_function_generic; - - - -/************************************************ - * generic external parametric function - ************************************************/ - -// prototype of a parametric external function -typedef struct -{ - // public members for core (have to be before private ones) - void (*evaluate)(void *, ext_fun_arg_t *, void **, ext_fun_arg_t *, void **); - // public members for interfaces - void (*get_nparam)(void *, int *); - void (*set_param)(void *, double *); - void (*set_param_sparse)(void *, int n_update, int *idx, double *); - // private members - void *ptr_ext_mem; // pointer to external memory - int (*fun)(void **, void **, void *); - double *p; // parameters - int np; // number of parameters - // ..... -} external_function_param_generic; - -// -acados_size_t external_function_param_generic_struct_size(); -// -void external_function_param_generic_set_fun(external_function_param_generic *fun, void *value); -// -acados_size_t external_function_param_generic_calculate_size(external_function_param_generic *fun, int np); -// -void external_function_param_generic_assign(external_function_param_generic *fun, void *mem); -// -void external_function_param_generic_wrapper(void *self, ext_fun_arg_t *type_in, void **in, ext_fun_arg_t *type_out, void **out); -// -void external_function_param_generic_get_nparam(void *self, int *np); -// -void external_function_param_generic_set_param(void *self, double *p); - - -/************************************************ - * casadi external function - ************************************************/ - -typedef struct -{ - // public members (have to be the same as in the prototype, and before the private ones) - void (*evaluate)(void *, ext_fun_arg_t *, void **, ext_fun_arg_t *, void **); - // private members - void *ptr_ext_mem; // pointer to external memory - int (*casadi_fun)(const double **, double **, int *, double *, void *); - int (*casadi_work)(int *, int *, int *, int *); - const int *(*casadi_sparsity_in)(int); - const int *(*casadi_sparsity_out)(int); - int (*casadi_n_in)(void); - int (*casadi_n_out)(void); - double **args; - double **res; - double *w; - int *iw; - int *args_size; // size of args[i] - int *res_size; // size of res[i] - int args_num; // number of args arrays - int args_size_tot; // total size of args arrays - int res_num; // number of res arrays - int res_size_tot; // total size of res arrays - int in_num; // number of input arrays - int out_num; // number of output arrays - int iw_size; // number of ints for worksapce - int w_size; // number of doubles for workspace -} external_function_casadi; - -// -acados_size_t external_function_casadi_struct_size(); -// -void external_function_casadi_set_fun(external_function_casadi *fun, void *value); -// -void external_function_casadi_set_work(external_function_casadi *fun, void *value); -// -void external_function_casadi_set_sparsity_in(external_function_casadi *fun, void *value); -// -void external_function_casadi_set_sparsity_out(external_function_casadi *fun, void *value); -// -void external_function_casadi_set_n_in(external_function_casadi *fun, void *value); -// -void external_function_casadi_set_n_out(external_function_casadi *fun, void *value); -// -acados_size_t external_function_casadi_calculate_size(external_function_casadi *fun); -// -void external_function_casadi_assign(external_function_casadi *fun, void *mem); -// -void external_function_casadi_wrapper(void *self, ext_fun_arg_t *type_in, void **in, - ext_fun_arg_t *type_out, void **out); - -/************************************************ - * casadi external parametric function - ************************************************/ - -typedef struct -{ - // public members for core (have to be the same as in the prototype, and before the private ones) - void (*evaluate)(void *, ext_fun_arg_t *, void **, ext_fun_arg_t *, void **); - // public members for interfaces - void (*get_nparam)(void *, int *); - void (*set_param)(void *, double *); - void (*set_param_sparse)(void *, int n_update, int *idx, double *); - // private members - void *ptr_ext_mem; // pointer to external memory - int (*casadi_fun)(const double **, double **, int *, double *, void *); - int (*casadi_work)(int *, int *, int *, int *); - const int *(*casadi_sparsity_in)(int); - const int *(*casadi_sparsity_out)(int); - int (*casadi_n_in)(void); - int (*casadi_n_out)(void); - double **args; - double **res; - double *w; - int *iw; - int *args_size; // size of args[i] - int *res_size; // size of res[i] - int args_num; // number of args arrays - int args_size_tot; // total size of args arrays - int res_num; // number of res arrays - int res_size_tot; // total size of res arrays - int in_num; // number of input arrays - int out_num; // number of output arrays - int iw_size; // number of ints for worksapce - int w_size; // number of doubles for workspace - int np; // number of parameters -} external_function_param_casadi; - -// -acados_size_t external_function_param_casadi_struct_size(); -// -void external_function_param_casadi_set_fun(external_function_param_casadi *fun, void *value); -// -void external_function_param_casadi_set_work(external_function_param_casadi *fun, void *value); -// -void external_function_param_casadi_set_sparsity_in(external_function_param_casadi *fun, void *value); -// -void external_function_param_casadi_set_sparsity_out(external_function_param_casadi *fun, void *value); -// -void external_function_param_casadi_set_n_in(external_function_param_casadi *fun, void *value); -// -void external_function_param_casadi_set_n_out(external_function_param_casadi *fun, void *value); -// -acados_size_t external_function_param_casadi_calculate_size(external_function_param_casadi *fun, int np); -// -void external_function_param_casadi_assign(external_function_param_casadi *fun, void *mem); -// -void external_function_param_casadi_wrapper(void *self, ext_fun_arg_t *type_in, void **in, - ext_fun_arg_t *type_out, void **out); -// -void external_function_param_casadi_get_nparam(void *self, int *np); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_UTILS_EXTERNAL_FUNCTION_GENERIC_H_ diff --git a/third_party/acados/include/acados/utils/math.h b/third_party/acados/include/acados/utils/math.h deleted file mode 100644 index 7156a82084..0000000000 --- a/third_party/acados/include/acados/utils/math.h +++ /dev/null @@ -1,103 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - -#ifndef ACADOS_UTILS_MATH_H_ -#define ACADOS_UTILS_MATH_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/utils/types.h" - -#if defined(__MABX2__) -double fmax(double a, double b); -int isnan(double x); -#endif - -#define MIN(a,b) (((a)<(b))?(a):(b)) -#define MAX(a,b) (((a)>(b))?(a):(b)) - -void dgemm_nn_3l(int m, int n, int k, double *A, int lda, double *B, int ldb, double *C, int ldc); -// void dgemv_n_3l(int m, int n, double *A, int lda, double *x, double *y); -// void dgemv_t_3l(int m, int n, double *A, int lda, double *x, double *y); -// void dcopy_3l(int n, double *x, int incx, double *y, int incy); -void daxpy_3l(int n, double da, double *dx, double *dy); -void dscal_3l(int n, double da, double *dx); -double twonormv(int n, double *ptrv); - -/* copies a matrix into another matrix */ -void dmcopy(int row, int col, double *ptrA, int lda, double *ptrB, int ldb); - -/* solution of a system of linear equations */ -void dgesv_3l(int n, int nrhs, double *A, int lda, int *ipiv, double *B, int ldb, int *info); - -/* matrix exponential */ -void expm(int row, double *A); - -int idamax_3l(int n, double *x); - -void dswap_3l(int n, double *x, int incx, double *y, int incy); - -void dger_3l(int m, int n, double alpha, double *x, int incx, double *y, int incy, double *A, - int lda); - -void dgetf2_3l(int m, int n, double *A, int lda, int *ipiv, int *info); - -void dlaswp_3l(int n, double *A, int lda, int k1, int k2, int *ipiv); - -void dtrsm_l_l_n_u_3l(int m, int n, double *A, int lda, double *B, int ldb); - -void dgetrs_3l(int n, int nrhs, double *A, int lda, int *ipiv, double *B, int ldb); - -void dgesv_3l(int n, int nrhs, double *A, int lda, int *ipiv, double *B, int ldb, int *info); - -double onenorm(int row, int col, double *ptrA); - -// double twonormv(int n, double *ptrv); - -void padeapprox(int m, int row, double *A); - -void expm(int row, double *A); - -// void d_compute_qp_size_ocp2dense_rev(int N, int *nx, int *nu, int *nb, int **hidxb, int *ng, -// int *nvd, int *ned, int *nbd, int *ngd); - -void acados_eigen_decomposition(int dim, double *A, double *V, double *d, double *e); - -double minimum_of_doubles(double *x, int n); - -void neville_algorithm(double xx, int n, double *x, double *Q, double *out); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_UTILS_MATH_H_ diff --git a/third_party/acados/include/acados/utils/mem.h b/third_party/acados/include/acados/utils/mem.h deleted file mode 100644 index 681a371e36..0000000000 --- a/third_party/acados/include/acados/utils/mem.h +++ /dev/null @@ -1,110 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_UTILS_MEM_H_ -#define ACADOS_UTILS_MEM_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include -#include - -#include "types.h" - -// blasfeo -#include "blasfeo/include/blasfeo_d_aux.h" -#include "blasfeo/include/blasfeo_d_aux_ext_dep.h" - -// TODO(dimitris): probably does not belong here -typedef struct -{ - int (*fun)(void *); - acados_size_t (*calculate_args_size)(void *); - void *(*assign_args)(void *); - void (*initialize_default_args)(void *); - acados_size_t (*calculate_memory_size)(void *); - void *(*assign_memory)(void *); - acados_size_t (*calculate_workspace_size)(void *); -} module_solver; - -// make int counter of memory multiple of a number (typically 8 or 64) -void make_int_multiple_of(acados_size_t num, acados_size_t *size); - -// align char pointer to number (typically 8 for pointers and doubles, -// 64 for blasfeo structs) and return offset -int align_char_to(int num, char **c_ptr); - -// switch between malloc and calloc (for valgrinding) -void *acados_malloc(size_t nitems, acados_size_t size); - -// uses always calloc -void *acados_calloc(size_t nitems, acados_size_t size); - -// allocate vector of pointers to vectors of doubles and advance pointer -void assign_and_advance_double_ptrs(int n, double ***v, char **ptr); - -// allocate vector of pointers to vectors of ints and advance pointer -void assign_and_advance_int_ptrs(int n, int ***v, char **ptr); - -// allocate vector of pointers to strvecs and advance pointer -void assign_and_advance_blasfeo_dvec_structs(int n, struct blasfeo_dvec **sv, char **ptr); - -// allocate vector of pointers to strmats and advance pointer -void assign_and_advance_blasfeo_dmat_structs(int n, struct blasfeo_dmat **sm, char **ptr); - -// allocate vector of pointers to vector of pointers to strmats and advance pointer -void assign_and_advance_blasfeo_dmat_ptrs(int n, struct blasfeo_dmat ***sm, char **ptr); - -// allocate vector of chars and advance pointer -void assign_and_advance_char(int n, char **v, char **ptr); - -// allocate vector of ints and advance pointer -void assign_and_advance_int(int n, int **v, char **ptr); - -// allocate vector of bools and advance pointer -void assign_and_advance_bool(int n, bool **v, char **ptr); - -// allocate vector of doubles and advance pointer -void assign_and_advance_double(int n, double **v, char **ptr); - -// allocate strvec and advance pointer -void assign_and_advance_blasfeo_dvec_mem(int n, struct blasfeo_dvec *sv, char **ptr); - -// allocate strmat and advance pointer -void assign_and_advance_blasfeo_dmat_mem(int m, int n, struct blasfeo_dmat *sA, char **ptr); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_UTILS_MEM_H_ diff --git a/third_party/acados/include/acados/utils/print.h b/third_party/acados/include/acados/utils/print.h deleted file mode 100644 index 824d3cee22..0000000000 --- a/third_party/acados/include/acados/utils/print.h +++ /dev/null @@ -1,110 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_UTILS_PRINT_H_ -#define ACADOS_UTILS_PRINT_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/dense_qp/dense_qp_common.h" -#include "acados/ocp_nlp/ocp_nlp_common.h" -#include "acados/ocp_qp/ocp_qp_common.h" -#include "acados/ocp_qp/ocp_qp_common_frontend.h" -#include "acados/utils/types.h" - -// void print_matrix(char *file_name, const real_t *matrix, const int_t nrows, const int_t ncols); - -// void print_matrix_name(char *file_name, char *name, const real_t *matrix, const int_t nrows, -// const int_t ncols); - -// void print_int_matrix(char *file_name, const int_t *matrix, const int_t nrows, const int_t ncols); - -// void print_array(char *file_name, real_t *array, int_t size); - -// void print_int_array(char *file_name, const int_t *array, int_t size); - -void read_matrix(const char *file_name, real_t *array, const int_t nrows, const int_t ncols); - -void write_double_vector_to_txt(real_t *vec, int_t n, const char *fname); - -// ocp nlp -// TODO(andrea): inconsistent naming -void ocp_nlp_dims_print(ocp_nlp_dims *dims); -// TODO(andrea): inconsistent naming -void ocp_nlp_out_print(ocp_nlp_dims *dims, ocp_nlp_out *nlp_out); -// TODO(andrea): inconsistent naming -void ocp_nlp_res_print(ocp_nlp_dims *dims, ocp_nlp_res *nlp_res); - -// ocp qp -// TODO: move printing routines below that print qp structures to HPIPM! -void print_ocp_qp_dims(ocp_qp_dims *dims); - -// void print_dense_qp_dims(dense_qp_dims *dims); - -void print_ocp_qp_in(ocp_qp_in *qp_in); - -void print_ocp_qp_in_to_file(FILE *file, ocp_qp_in *qp_in); - -void print_ocp_qp_out(ocp_qp_out *qp_out); - -void print_ocp_qp_out_to_file(FILE *file, ocp_qp_out *qp_out); - -void print_ocp_qp_res(ocp_qp_res *qp_res); - -void print_dense_qp_in(dense_qp_in *qp_in); -// void print_ocp_qp_in_to_string(char string_out[], ocp_qp_in *qp_in); - -// void print_ocp_qp_out_to_string(char string_out[], ocp_qp_out *qp_out); - -// void print_colmaj_ocp_qp_in(colmaj_ocp_qp_in *qp); - -// void print_colmaj_ocp_qp_in_to_file(colmaj_ocp_qp_in *qp); - -// void print_colmaj_ocp_qp_out(char *filename, colmaj_ocp_qp_in *qp, colmaj_ocp_qp_out *out); - -void print_qp_info(qp_info *info); - -// void acados_warning(char warning_string[]); - -// void acados_error(char error_string[]); - -// void acados_not_implemented(char feature_string[]); - -// blasfeo -// void print_blasfeo_target(); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_UTILS_PRINT_H_ diff --git a/third_party/acados/include/acados/utils/strsep.h b/third_party/acados/include/acados/utils/strsep.h deleted file mode 100644 index 62bdfb4891..0000000000 --- a/third_party/acados/include/acados/utils/strsep.h +++ /dev/null @@ -1,69 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_UTILS_STRSEP_H_ -#define ACADOS_UTILS_STRSEP_H_ - -#ifdef __cplusplus -#include -#define STD(x) std::x -namespace std -{ -#else -#include -#define STD(x) x -#endif - -char* strsep_acados(char** stringp, const char* delim) -{ - char* result; - - if ((stringp == NULL) || (*stringp == NULL)) return NULL; - - result = *stringp; - - while (**stringp && !STD(strchr)(delim, **stringp)) ++*stringp; - - if (**stringp) - *(*stringp)++ = '\0'; - else - *stringp = NULL; - - return result; -} - -#ifdef __cplusplus -} // namespace std -#endif - -#undef STD - -#endif // ACADOS_UTILS_STRSEP_H_ diff --git a/third_party/acados/include/acados/utils/timing.h b/third_party/acados/include/acados/utils/timing.h deleted file mode 100644 index b0955932da..0000000000 --- a/third_party/acados/include/acados/utils/timing.h +++ /dev/null @@ -1,122 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_UTILS_TIMING_H_ -#define ACADOS_UTILS_TIMING_H_ - -#include "acados/utils/types.h" - -#ifdef __cplusplus -extern "C" { -#endif - -#ifdef MEASURE_TIMINGS -#if (defined _WIN32 || defined _WIN64) && !(defined __MINGW32__ || defined __MINGW64__) - -/* Use Windows QueryPerformanceCounter for timing. */ -#include - -/** A structure for keeping internal timer data. */ -typedef struct acados_timer_ -{ - LARGE_INTEGER tic; - LARGE_INTEGER toc; - LARGE_INTEGER freq; -} acados_timer; - -#elif defined(__APPLE__) - -#include - -/** A structure for keeping internal timer data. */ -typedef struct acados_timer_ -{ - uint64_t tic; - uint64_t toc; - mach_timebase_info_data_t tinfo; -} acados_timer; - -#elif defined(__MABX2__) - -#include - -typedef struct acados_timer_ -{ - double time; -} acados_timer; - -#else - -/* Use POSIX clock_gettime() for timing on non-Windows machines. */ -#include - -#if (__STDC_VERSION__ >= 199901L) && !(defined __MINGW32__ || defined __MINGW64__) // C99 Mode - -#include -#include - -typedef struct acados_timer_ -{ - struct timeval tic; - struct timeval toc; -} acados_timer; - -#else // ANSI C Mode - -/** A structure for keeping internal timer data. */ -typedef struct acados_timer_ -{ - struct timespec tic; - struct timespec toc; -} acados_timer; - -#endif // __STDC_VERSION__ >= 199901L - -#endif // (defined _WIN32 || defined _WIN64) - -#else - -// Dummy type when timings are off -typedef real_t acados_timer; - -#endif // MEASURE_TIMINGS - -/** A function for measurement of the current time. */ -void acados_tic(acados_timer* t); - -/** A function which returns the elapsed time. */ -real_t acados_toc(acados_timer* t); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_UTILS_TIMING_H_ diff --git a/third_party/acados/include/acados/utils/types.h b/third_party/acados/include/acados/utils/types.h deleted file mode 100644 index a27ef9e552..0000000000 --- a/third_party/acados/include/acados/utils/types.h +++ /dev/null @@ -1,91 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_UTILS_TYPES_H_ -#define ACADOS_UTILS_TYPES_H_ - -/* Symbol visibility in DLLs */ -#ifndef ACADOS_SYMBOL_EXPORT - #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) - #if defined(STATIC_LINKED) - #define ACADOS_SYMBOL_EXPORT - #else - #define ACADOS_SYMBOL_EXPORT __declspec(dllexport) - #endif - #elif defined(__GNUC__) && ((__GNUC__ >= 4) || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) - #define ACADOS_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) - #else - #define ACADOS_SYMBOL_EXPORT - #endif -#endif - -#ifdef __cplusplus -extern "C" { -#endif - -#include -#include - -#define MAX_STR_LEN 256 -#define ACADOS_EPS 1e-12 -#define ACADOS_NEG_INFTY -1.0e9 -#define ACADOS_POS_INFTY +1.0e9 -#define UNUSED(x) ((void)(x)) - - - -typedef double real_t; -typedef int int_t; -typedef size_t acados_size_t; - - -typedef int (*casadi_function_t)(const double** arg, double** res, int* iw, double* w, void* mem); - - - -// enum of return values -enum return_values -{ - ACADOS_SUCCESS, - ACADOS_NAN_DETECTED, - ACADOS_MAXITER, - ACADOS_MINSTEP, - ACADOS_QP_FAILURE, - ACADOS_READY, -}; - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_UTILS_TYPES_H_ diff --git a/third_party/acados/include/acados_c/condensing_interface.h b/third_party/acados/include/acados_c/condensing_interface.h deleted file mode 100644 index b4302078d6..0000000000 --- a/third_party/acados/include/acados_c/condensing_interface.h +++ /dev/null @@ -1,81 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef INTERFACES_ACADOS_C_CONDENSING_INTERFACE_H_ -#define INTERFACES_ACADOS_C_CONDENSING_INTERFACE_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/ocp_qp/ocp_qp_full_condensing.h" -#include "acados/ocp_qp/ocp_qp_partial_condensing.h" - -typedef enum { - PARTIAL_CONDENSING, - FULL_CONDENSING, -} condensing_t; - -typedef struct -{ - condensing_t condensing_type; -} condensing_plan; - -typedef struct -{ - ocp_qp_xcond_config *config; - void *dims; - void *opts; - void *mem; - void *work; -} condensing_module; - -ocp_qp_xcond_config *ocp_qp_condensing_config_create(condensing_plan *plan); -// -void *ocp_qp_condensing_opts_create(ocp_qp_xcond_config *config, void *dims_); -// -acados_size_t ocp_qp_condensing_calculate_size(ocp_qp_xcond_config *config, void *dims_, void *opts_); -// -condensing_module *ocp_qp_condensing_assign(ocp_qp_xcond_config *config, void *dims_, - void *opts_, void *raw_memory); -// -condensing_module *ocp_qp_condensing_create(ocp_qp_xcond_config *config, void *dims_, - void *opts_); -// -int ocp_qp_condense(condensing_module *module, void *qp_in, void *qp_out); -// -int ocp_qp_expand(condensing_module *module, void *qp_in, void *qp_out); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // INTERFACES_ACADOS_C_CONDENSING_INTERFACE_H_ diff --git a/third_party/acados/include/acados_c/dense_qp_interface.h b/third_party/acados/include/acados_c/dense_qp_interface.h deleted file mode 100644 index b3af4bf682..0000000000 --- a/third_party/acados/include/acados_c/dense_qp_interface.h +++ /dev/null @@ -1,91 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef INTERFACES_ACADOS_C_DENSE_QP_INTERFACE_H_ -#define INTERFACES_ACADOS_C_DENSE_QP_INTERFACE_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/dense_qp/dense_qp_common.h" - -typedef enum { DENSE_QP_HPIPM, DENSE_QP_QORE, DENSE_QP_QPOASES, DENSE_QP_OOQP, DENSE_QP_DAQP } dense_qp_solver_t; - -typedef struct -{ - dense_qp_solver_t qp_solver; -} dense_qp_solver_plan; - -typedef struct -{ - qp_solver_config *config; - void *dims; - void *opts; - void *mem; - void *work; -} dense_qp_solver; - -qp_solver_config *dense_qp_config_create(dense_qp_solver_plan *plan); -// -dense_qp_dims *dense_qp_dims_create(); -// -dense_qp_in *dense_qp_in_create(qp_solver_config *config, dense_qp_dims *dims); -// -dense_qp_out *dense_qp_out_create(qp_solver_config *config, dense_qp_dims *dims); -// -void *dense_qp_opts_create(qp_solver_config *config, dense_qp_dims *dims); -// -acados_size_t dense_qp_calculate_size(qp_solver_config *config, dense_qp_dims *dims, void *opts_); -// -dense_qp_solver *dense_qp_assign(qp_solver_config *config, dense_qp_dims *dims, void *opts_, - void *raw_memory); -// -dense_qp_solver *dense_qp_create(qp_solver_config *config, dense_qp_dims *dims, void *opts_); -// -int dense_qp_solve(dense_qp_solver *solver, dense_qp_in *qp_in, dense_qp_out *qp_out); -// -void dense_qp_inf_norm_residuals(dense_qp_dims *dims, dense_qp_in *qp_in, dense_qp_out *qp_out, - double *res); -// -bool dense_qp_set_field_double_array(const char *field, double *arr, dense_qp_in *qp_in); -// -bool dense_qp_set_field_int_array(const char *field, int *arr, dense_qp_in *qp_in); -// -bool dense_qp_get_field_double_array(const char *field, dense_qp_in *qp_in, double *arr); -// -bool dense_qp_get_field_int_array(const char *field, dense_qp_in *qp_in, int *arr); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // INTERFACES_ACADOS_C_DENSE_QP_INTERFACE_H_ diff --git a/third_party/acados/include/acados_c/external_function_interface.h b/third_party/acados/include/acados_c/external_function_interface.h deleted file mode 100644 index d4f52db850..0000000000 --- a/third_party/acados/include/acados_c/external_function_interface.h +++ /dev/null @@ -1,89 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef INTERFACES_ACADOS_C_EXTERNAL_FUNCTION_INTERFACE_H_ -#define INTERFACES_ACADOS_C_EXTERNAL_FUNCTION_INTERFACE_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/utils/external_function_generic.h" - - - -/************************************************ - * generic external parametric function - ************************************************/ - -// -void external_function_param_generic_create(external_function_param_generic *fun, int np); -// -void external_function_param_generic_free(external_function_param_generic *fun); - - - -/************************************************ - * casadi external function - ************************************************/ - -// -void external_function_casadi_create(external_function_casadi *fun); -// -void external_function_casadi_free(external_function_casadi *fun); -// -void external_function_casadi_create_array(int size, external_function_casadi *funs); -// -void external_function_casadi_free_array(int size, external_function_casadi *funs); - - - -/************************************************ - * casadi external parametric function - ************************************************/ - -// -void external_function_param_casadi_create(external_function_param_casadi *fun, int np); -// -void external_function_param_casadi_free(external_function_param_casadi *fun); -// -void external_function_param_casadi_create_array(int size, external_function_param_casadi *funs, - int np); -// -void external_function_param_casadi_free_array(int size, external_function_param_casadi *funs); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // INTERFACES_ACADOS_C_EXTERNAL_FUNCTION_INTERFACE_H_ diff --git a/third_party/acados/include/acados_c/ocp_nlp_interface.h b/third_party/acados/include/acados_c/ocp_nlp_interface.h deleted file mode 100644 index dd3e596f8b..0000000000 --- a/third_party/acados/include/acados_c/ocp_nlp_interface.h +++ /dev/null @@ -1,428 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef INTERFACES_ACADOS_C_OCP_NLP_INTERFACE_H_ -#define INTERFACES_ACADOS_C_OCP_NLP_INTERFACE_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// acados -#include "acados/ocp_nlp/ocp_nlp_common.h" -#include "acados/ocp_nlp/ocp_nlp_constraints_bgh.h" -#include "acados/sim/sim_erk_integrator.h" -#include "acados/sim/sim_irk_integrator.h" -#include "acados/sim/sim_lifted_irk_integrator.h" -#include "acados/sim/sim_gnsf.h" -#include "acados/utils/types.h" -// acados_c -#include "acados_c/ocp_qp_interface.h" -#include "acados_c/sim_interface.h" - - -/// Solution methods for optimal control problems. -typedef enum -{ - SQP, - SQP_RTI, - INVALID_NLP_SOLVER, -} ocp_nlp_solver_t; - - -/// Types of the cost function. -typedef enum -{ - LINEAR_LS, - NONLINEAR_LS, - CONVEX_OVER_NONLINEAR, - EXTERNAL, - INVALID_COST, -} ocp_nlp_cost_t; - - -/// Types of the system dynamics, discrete or continuous time. -typedef enum -{ - CONTINUOUS_MODEL, - DISCRETE_MODEL, - INVALID_DYNAMICS, -} ocp_nlp_dynamics_t; - - -/// Constraint types -typedef enum -{ - /// Comprises simple bounds, polytopic constraints, - /// general non-linear constraints. - BGH, - - /// Comprises simple bounds, polytopic constraints, - /// general non-linear constraints, and positive definite constraints. - BGP, - - INVALID_CONSTRAINT, -} ocp_nlp_constraints_t; - - -/// Regularization types -typedef enum -{ - NO_REGULARIZE, - MIRROR, - PROJECT, - PROJECT_REDUC_HESS, - CONVEXIFY, - INVALID_REGULARIZE, -} ocp_nlp_reg_t; - - -/// Structure to store the configuration of a non-linear program -typedef struct ocp_nlp_plan_t -{ - /// QP solver configuration. - ocp_qp_solver_plan_t ocp_qp_solver_plan; - - /// Simulation solver configuration for each stage. - sim_solver_plan_t *sim_solver_plan; - - /// Nlp solver type. - ocp_nlp_solver_t nlp_solver; - - /// Regularization type, defaults to no regularization. - ocp_nlp_reg_t regularization; - - /// Cost type for each stage. - ocp_nlp_cost_t *nlp_cost; - - /// Dynamics type for each stage. - ocp_nlp_dynamics_t *nlp_dynamics; - - /// Constraints type for each stage. - ocp_nlp_constraints_t *nlp_constraints; - - /// Horizon length. - int N; - -} ocp_nlp_plan_t; - - -/// Structure to store the state/configuration for the non-linear programming solver -typedef struct ocp_nlp_solver -{ - ocp_nlp_config *config; - void *dims; - void *opts; - void *mem; - void *work; -} ocp_nlp_solver; - - -/// Constructs an empty plan struct (user nlp configuration), all fields are set to a -/// default/invalid state. -/// -/// \param N Horizon length -ACADOS_SYMBOL_EXPORT ocp_nlp_plan_t *ocp_nlp_plan_create(int N); - -/// Destructor for plan struct, frees memory. -/// -/// \param plan_ The plan struct to destroy. -ACADOS_SYMBOL_EXPORT void ocp_nlp_plan_destroy(void* plan_); - - -/// Constructs an nlp configuration struct from a plan. -/// -/// \param plan The plan (user nlp configuration). -ACADOS_SYMBOL_EXPORT ocp_nlp_config *ocp_nlp_config_create(ocp_nlp_plan_t plan); - -/// Desctructor of the nlp configuration. -/// -/// \param config_ The configuration struct. -ACADOS_SYMBOL_EXPORT void ocp_nlp_config_destroy(void *config_); - - -/// Constructs an struct that contains the dimensions of the variables. -/// -/// \param config_ The configuration struct. -ACADOS_SYMBOL_EXPORT ocp_nlp_dims *ocp_nlp_dims_create(void *config_); - -/// Destructor of The dimension struct. -/// -/// \param dims_ The dimension struct. -ACADOS_SYMBOL_EXPORT void ocp_nlp_dims_destroy(void *dims_); - - -/// Constructs an input struct for a non-linear programs. -/// -/// \param config The configuration struct. -/// \param dims The dimension struct. -ACADOS_SYMBOL_EXPORT ocp_nlp_in *ocp_nlp_in_create(ocp_nlp_config *config, ocp_nlp_dims *dims); - -/// Destructor of the inputs struct. -/// -/// \param in The inputs struct. -ACADOS_SYMBOL_EXPORT void ocp_nlp_in_destroy(void *in); - - -/// Sets the sampling times for the given stage. -/// -/// \param config The configuration struct. -/// \param dims The dimension struct. -/// \param in The inputs struct. -/// \param stage Stage number. -/// \param field Has to be "Ts" (TBC other options). -/// \param value The sampling times (floating point). -ACADOS_SYMBOL_EXPORT void ocp_nlp_in_set(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, int stage, - const char *field, void *value); - -/// -// void ocp_nlp_in_get(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, int stage, -// const char *field, void *value); - -/// Sets the function pointers to the dynamics functions for the given stage. -/// -/// \param config The configuration struct. -/// \param dims The dimension struct. -/// \param in The inputs struct. -/// \param stage Stage number. -/// \param fun_type The name of the function type, either impl_ode_fun, -/// impl_ode_fun_jac_x_xdot, impl_ode_jac_x_xdot_u (TBC) -/// \param fun_ptr Function pointer to the dynamics function. -ACADOS_SYMBOL_EXPORT int ocp_nlp_dynamics_model_set(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, - int stage, const char *fun_type, void *fun_ptr); - - -/// Sets the function pointers to the cost functions for the given stage. -/// -/// \param config The configuration struct. -/// \param dims The dimension struct. -/// \param in The inputs struct. -/// \param stage Stage number. -/// \param field The name of the field, either nls_res_jac, -/// y_ref, W (others TBC) -/// \param value Cost values. -ACADOS_SYMBOL_EXPORT int ocp_nlp_cost_model_set(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, - int stage, const char *field, void *value); - - -/// Sets the function pointers to the constraints functions for the given stage. -/// -/// \param config The configuration struct. -/// \param dims The dimension struct. -/// \param in The inputs struct. -/// \param stage Stage number. -/// \param field The name of the field, either lb, ub (others TBC) -/// \param value Constraints function or values. -ACADOS_SYMBOL_EXPORT int ocp_nlp_constraints_model_set(ocp_nlp_config *config, ocp_nlp_dims *dims, - ocp_nlp_in *in, int stage, const char *field, void *value); - -/// -ACADOS_SYMBOL_EXPORT void ocp_nlp_constraints_model_get(ocp_nlp_config *config, ocp_nlp_dims *dims, - ocp_nlp_in *in, int stage, const char *field, void *value); - -/* out */ - -/// Constructs an output struct for the non-linear program. -/// -/// \param config The configuration struct. -/// \param dims The dimension struct. -ACADOS_SYMBOL_EXPORT ocp_nlp_out *ocp_nlp_out_create(ocp_nlp_config *config, ocp_nlp_dims *dims); - -/// Destructor of the output struct. -/// -/// \param out The output struct. -ACADOS_SYMBOL_EXPORT void ocp_nlp_out_destroy(void *out); - - -/// Sets fields in the output struct of an nlp solver, used to initialize the solver. -/// -/// \param config The configuration struct. -/// \param dims The dimension struct. -/// \param out The output struct. -/// \param stage Stage number. -/// \param field The name of the field, either x, u, pi. -/// \param value Initialization values. -ACADOS_SYMBOL_EXPORT void ocp_nlp_out_set(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out, - int stage, const char *field, void *value); - - -/// Gets values of fields in the output struct of an nlp solver. -/// -/// \param config The configuration struct. -/// \param dims The dimension struct. -/// \param out The output struct. -/// \param stage Stage number. -/// \param field The name of the field, either x, u, z, pi. -/// \param value Pointer to the output memory. -ACADOS_SYMBOL_EXPORT void ocp_nlp_out_get(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out, - int stage, const char *field, void *value); - -// -ACADOS_SYMBOL_EXPORT void ocp_nlp_get_at_stage(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_solver *solver, - int stage, const char *field, void *value); - -// TODO(andrea): remove this once/if the MATLAB interface uses the new setters below? -ACADOS_SYMBOL_EXPORT int ocp_nlp_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out, - int stage, const char *field); - -ACADOS_SYMBOL_EXPORT void ocp_nlp_constraint_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out, - int stage, const char *field, int *dims_out); - -ACADOS_SYMBOL_EXPORT void ocp_nlp_cost_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out, - int stage, const char *field, int *dims_out); - -ACADOS_SYMBOL_EXPORT void ocp_nlp_qp_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out, - int stage, const char *field, int *dims_out); - -/* opts */ - -/// Creates an options struct for the non-linear program. -/// -/// \param config The configuration struct. -/// \param dims The dimension struct. -ACADOS_SYMBOL_EXPORT void *ocp_nlp_solver_opts_create(ocp_nlp_config *config, ocp_nlp_dims *dims); - -/// Destructor of the options. -/// -/// \param opts The options struct. -ACADOS_SYMBOL_EXPORT void ocp_nlp_solver_opts_destroy(void *opts); - -/// Sets an option. -/// -/// \param config The configuration struct. -/// \param opts_ The options struct. -/// \param field Name of the option. -/// \param value Value of the option. -ACADOS_SYMBOL_EXPORT void ocp_nlp_solver_opts_set(ocp_nlp_config *config, void *opts_, const char *field, void* value); - - -// ACADOS_SYMBOL_EXPORT void ocp_nlp_solver_opts_get(ocp_nlp_config *config, void *opts_, const char *field, void* value); - - -ACADOS_SYMBOL_EXPORT void ocp_nlp_solver_opts_set_at_stage(ocp_nlp_config *config, void *opts_, int stage, const char *field, void* value); - - -/// TBC -/// Updates the options. -/// -/// \param config The configuration struct. -/// \param dims The dimension struct. -/// \param opts_ The options struct. -ACADOS_SYMBOL_EXPORT void ocp_nlp_solver_opts_update(ocp_nlp_config *config, ocp_nlp_dims *dims, void *opts_); - - -/* solver */ - -/// Creates an ocp solver. -/// -/// \param config The configuration struct. -/// \param dims The dimension struct. -/// \param opts_ The options struct. -/// \return The solver. -ACADOS_SYMBOL_EXPORT ocp_nlp_solver *ocp_nlp_solver_create(ocp_nlp_config *config, ocp_nlp_dims *dims, void *opts_); - -/// Destructor of the solver. -/// -/// \param solver The solver struct. -ACADOS_SYMBOL_EXPORT void ocp_nlp_solver_destroy(void *solver); - -/// Solves the optimal control problem. Call ocp_nlp_precompute before -/// calling this functions (TBC). -/// -/// \param solver The solver struct. -/// \param nlp_in The inputs struct. -/// \param nlp_out The output struct. -ACADOS_SYMBOL_EXPORT int ocp_nlp_solve(ocp_nlp_solver *solver, ocp_nlp_in *nlp_in, ocp_nlp_out *nlp_out); - - - -/// Resets the memory of the QP solver -/// -/// \param solver The solver struct. -/// \param nlp_in The inputs struct. -/// \param nlp_out The output struct. -ACADOS_SYMBOL_EXPORT void ocp_nlp_solver_reset_qp_memory(ocp_nlp_solver *solver, ocp_nlp_in *nlp_in, ocp_nlp_out *nlp_out); - - -/// Performs precomputations for the solver. Needs to be called before -/// ocl_nlp_solve (TBC). -/// -/// \param solver The solver struct. -/// \param nlp_in The inputs struct. -/// \param nlp_out The output struct. -ACADOS_SYMBOL_EXPORT int ocp_nlp_precompute(ocp_nlp_solver *solver, ocp_nlp_in *nlp_in, ocp_nlp_out *nlp_out); - - -/// Computes cost function value. -/// -/// \param solver The solver struct. -/// \param nlp_in The inputs struct. -/// \param nlp_out The output struct. -ACADOS_SYMBOL_EXPORT void ocp_nlp_eval_cost(ocp_nlp_solver *solver, ocp_nlp_in *nlp_in, ocp_nlp_out *nlp_out); - - -/// Computes the residuals. -/// -/// \param solver The solver struct. -/// \param nlp_in The inputs struct. -/// \param nlp_out The output struct. -ACADOS_SYMBOL_EXPORT void ocp_nlp_eval_residuals(ocp_nlp_solver *solver, ocp_nlp_in *nlp_in, ocp_nlp_out *nlp_out); - - -// -ACADOS_SYMBOL_EXPORT void ocp_nlp_eval_param_sens(ocp_nlp_solver *solver, char *field, int stage, int index, ocp_nlp_out *sens_nlp_out); - -/* get */ -/// \param config The configuration struct. -/// \param solver The solver struct. -/// \param field Supports "sqp_iter", "status", "nlp_res", "time_tot", ... -/// \param return_value_ Pointer to the output memory. -ACADOS_SYMBOL_EXPORT void ocp_nlp_get(ocp_nlp_config *config, ocp_nlp_solver *solver, - const char *field, void *return_value_); - -/* set */ -/// Sets the initial guesses for the integrator for the given stage. -/// -/// \param config The configuration struct. -/// \param solver The ocp_nlp_solver struct. -/// \param stage Stage number. -/// \param field Supports "z_guess", "xdot_guess" (IRK), "phi_guess" (GNSF-IRK) -/// \param value The initial guess for the algebraic variables in the integrator (if continuous model is used). -ACADOS_SYMBOL_EXPORT void ocp_nlp_set(ocp_nlp_config *config, ocp_nlp_solver *solver, - int stage, const char *field, void *value); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // INTERFACES_ACADOS_C_OCP_NLP_INTERFACE_H_ diff --git a/third_party/acados/include/acados_c/ocp_qp_interface.h b/third_party/acados/include/acados_c/ocp_qp_interface.h deleted file mode 100644 index 3dc3f1a532..0000000000 --- a/third_party/acados/include/acados_c/ocp_qp_interface.h +++ /dev/null @@ -1,263 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef INTERFACES_ACADOS_C_OCP_QP_INTERFACE_H_ -#define INTERFACES_ACADOS_C_OCP_QP_INTERFACE_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/ocp_qp/ocp_qp_common.h" -#include "acados/ocp_qp/ocp_qp_xcond_solver.h" - - -/// QP solver types (Enumeration). -/// -/// Full list of fields: -/// PARTIAL_CONDENSING_HPIPM -/// PARTIAL_CONDENSING_HPMPC -/// PARTIAL_CONDENSING_OOQP -/// PARTIAL_CONDENSING_OSQP -/// PARTIAL_CONDENSING_QPDUNES -/// FULL_CONDENSING_HPIPM -/// FULL_CONDENSING_QPOASES -/// FULL_CONDENSING_QORE -/// FULL_CONDENSING_OOQP -/// INVALID_QP_SOLVER -/// -/// Note: In this enumeration the partial condensing solvers have to be -/// specified before the full condensing solvers. -typedef enum { - PARTIAL_CONDENSING_HPIPM, -#ifdef ACADOS_WITH_HPMPC - PARTIAL_CONDENSING_HPMPC, -#else - PARTIAL_CONDENSING_HPMPC_NOT_AVAILABLE, -#endif -#ifdef ACADOS_WITH_OOQP - PARTIAL_CONDENSING_OOQP, -#else - PARTIAL_CONDENSING_OOQP_NOT_AVAILABLE, -#endif -#ifdef ACADOS_WITH_OSQP - PARTIAL_CONDENSING_OSQP, -#else - PARTIAL_CONDENSING_OSQP_NOT_AVAILABLE, -#endif -#ifdef ACADOS_WITH_QPDUNES - PARTIAL_CONDENSING_QPDUNES, -#else - PARTIAL_CONDENSING_QPDUNES_NOT_AVAILABLE, -#endif - FULL_CONDENSING_HPIPM, -#ifdef ACADOS_WITH_QPOASES - FULL_CONDENSING_QPOASES, -#else - FULL_CONDENSING_QPOASES_NOT_AVAILABLE, -#endif -#ifdef ACADOS_WITH_DAQP - FULL_CONDENSING_DAQP, -#else - FULL_CONDENSING_DAQP_NOT_AVAILABLE, -#endif -#ifdef ACADOS_WITH_QORE - FULL_CONDENSING_QORE, -#else - FULL_CONDENSING_QORE_NOT_AVAILABLE, -#endif -#ifdef ACADOS_WITH_OOQP - FULL_CONDENSING_OOQP, -#else - FULL_CONDENSING_OOQP_NOT_AVAILABLE, -#endif - INVALID_QP_SOLVER, -} ocp_qp_solver_t; - - -/// Struct containing qp solver -typedef struct -{ - ocp_qp_solver_t qp_solver; -} ocp_qp_solver_plan_t; - - -/// Linear ocp configuration. -typedef struct -{ - ocp_qp_xcond_solver_config *config; - ocp_qp_xcond_solver_dims *dims; - void *opts; - void *mem; - void *work; -} ocp_qp_solver; - - -/// Initializes the qp solver configuration. -/// TBC should this be private/static - no, used in ocp_nlp -void ocp_qp_xcond_solver_config_initialize_from_plan( - ocp_qp_solver_t solver_name, ocp_qp_xcond_solver_config *solver_config); - -/// Constructs a qp solver config and Initializes with default values. -/// -/// \param plan The qp solver plan struct. -ocp_qp_xcond_solver_config *ocp_qp_xcond_solver_config_create(ocp_qp_solver_plan_t plan); - -/// Destructor for config struct, frees memory. -/// -/// \param config The config object to destroy. -void ocp_qp_xcond_solver_config_free(ocp_qp_xcond_solver_config *config); - - -/// Constructs a struct that contains the dimensions for the variables of the qp. -/// -/// \param N The number of variables. -ocp_qp_dims *ocp_qp_dims_create(int N); - -/// Destructor of The dimension struct. -/// -/// \param dims The dimension struct. -void ocp_qp_dims_free(void *dims); - -// -ocp_qp_xcond_solver_dims *ocp_qp_xcond_solver_dims_create(ocp_qp_xcond_solver_config *config, int N); -// -ocp_qp_xcond_solver_dims *ocp_qp_xcond_solver_dims_create_from_ocp_qp_dims( - ocp_qp_xcond_solver_config *config, ocp_qp_dims *dims); -// -void ocp_qp_xcond_solver_dims_free(ocp_qp_xcond_solver_dims *dims_); - -void ocp_qp_xcond_solver_dims_set(void *config_, ocp_qp_xcond_solver_dims *dims, - int stage, const char *field, int* value); - - -/// Constructs an input object for the qp. -/// -/// \param dims The dimension struct. -ocp_qp_in *ocp_qp_in_create(ocp_qp_dims *dims); - - -void ocp_qp_in_set(ocp_qp_xcond_solver_config *config, ocp_qp_in *in, - int stage, char *field, void *value); - -/// Destructor of the inputs struct. -/// -/// \param in_ The inputs struct. -void ocp_qp_in_free(void *in_); - - -/// Constructs an outputs object for the qp. -/// -/// \param dims The dimension struct. -ocp_qp_out *ocp_qp_out_create(ocp_qp_dims *dims); - -/// Destructor of the output struct. -/// -/// \param out_ The output struct. -void ocp_qp_out_free(void *out_); - - -/// Getter of output struct -void ocp_qp_out_get(ocp_qp_out *out, const char *field, void *value); - - -/// Constructs an options object for the qp. -/// -/// \param config The configuration struct. -/// \param dims The dimension struct. -void *ocp_qp_xcond_solver_opts_create(ocp_qp_xcond_solver_config *config, - ocp_qp_xcond_solver_dims *dims); - -/// Destructor of the options struct. -/// -/// \param opts The options struct to destroy. -void ocp_qp_xcond_solver_opts_free(ocp_qp_xcond_solver_opts *opts); - - -/// Setter of the options struct. -/// -/// \param opts The options struct. -void ocp_qp_xcond_solver_opts_set(ocp_qp_xcond_solver_config *config, - ocp_qp_xcond_solver_opts *opts, const char *field, void* value); - -/// TBC Should be private/static? -acados_size_t ocp_qp_calculate_size(ocp_qp_xcond_solver_config *config, ocp_qp_xcond_solver_dims *dims, void *opts_); - - -/// TBC Reserves memory? TBC Should this be private? -/// -/// \param config The configuration struct. -/// \param dims The dimension struct. -/// \param opts_ The options struct. -/// \param raw_memory Pointer to raw memory to assign to qp solver. -ocp_qp_solver *ocp_qp_assign(ocp_qp_xcond_solver_config *config, ocp_qp_xcond_solver_dims *dims, - void *opts_, void *raw_memory); - -/// Creates a qp solver. Reserves memory. -/// -/// \param config The configuration struct. -/// \param dims The dimension struct. -/// \param opts_ The options struct. -ocp_qp_solver *ocp_qp_create(ocp_qp_xcond_solver_config *config, - ocp_qp_xcond_solver_dims *dims, void *opts_); - - -/// Destroys a qp solver. Frees memory. -/// -/// \param solver The qp solver -void ocp_qp_solver_destroy(ocp_qp_solver *solver); - -void ocp_qp_x_cond_solver_free(ocp_qp_xcond_solver_config *config, - ocp_qp_xcond_solver_dims *dims, void *opts_); - - -/// Solves the qp. -/// -/// \param solver The solver. -/// \param qp_in The inputs struct. -/// \param qp_out The output struct. -int ocp_qp_solve(ocp_qp_solver *solver, ocp_qp_in *qp_in, ocp_qp_out *qp_out); - - -/// Calculates the infinity norm of the residuals. -/// -/// \param dims The dimension struct. -/// \param qp_in The inputs struct. -/// \param qp_out The output struct. -/// \param res Output array for the residuals. -void ocp_qp_inf_norm_residuals(ocp_qp_dims *dims, ocp_qp_in *qp_in, ocp_qp_out *qp_out, - double *res); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // INTERFACES_ACADOS_C_OCP_QP_INTERFACE_H_ diff --git a/third_party/acados/include/acados_c/sim_interface.h b/third_party/acados/include/acados_c/sim_interface.h deleted file mode 100644 index 09a05d6995..0000000000 --- a/third_party/acados/include/acados_c/sim_interface.h +++ /dev/null @@ -1,137 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef INTERFACES_ACADOS_C_SIM_INTERFACE_H_ -#define INTERFACES_ACADOS_C_SIM_INTERFACE_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/sim/sim_common.h" - - - -typedef enum -{ - ERK, - IRK, - GNSF, - LIFTED_IRK, - INVALID_SIM_SOLVER, -} sim_solver_t; - - - -typedef struct -{ - sim_solver_t sim_solver; -} sim_solver_plan_t; - - - -typedef struct -{ - sim_config *config; - void *dims; - void *opts; - void *mem; - void *work; -} sim_solver; - - - -/* config */ -// -ACADOS_SYMBOL_EXPORT sim_config *sim_config_create(sim_solver_plan_t plan); -// -ACADOS_SYMBOL_EXPORT void sim_config_destroy(void *config); - -/* dims */ -// -ACADOS_SYMBOL_EXPORT void *sim_dims_create(void *config_); -// -ACADOS_SYMBOL_EXPORT void sim_dims_destroy(void *dims); -// -ACADOS_SYMBOL_EXPORT void sim_dims_set(sim_config *config, void *dims, const char *field, const int* value); -// -ACADOS_SYMBOL_EXPORT void sim_dims_get(sim_config *config, void *dims, const char *field, int* value); -// -ACADOS_SYMBOL_EXPORT void sim_dims_get_from_attr(sim_config *config, void *dims, const char *field, int *dims_out); - -/* in */ -// -ACADOS_SYMBOL_EXPORT sim_in *sim_in_create(sim_config *config, void *dims); -// -ACADOS_SYMBOL_EXPORT void sim_in_destroy(void *out); -// -ACADOS_SYMBOL_EXPORT int sim_in_set(void *config_, void *dims_, sim_in *in, const char *field, void *value); - - -/* out */ -// -ACADOS_SYMBOL_EXPORT sim_out *sim_out_create(sim_config *config, void *dims); -// -ACADOS_SYMBOL_EXPORT void sim_out_destroy(void *out); -// -ACADOS_SYMBOL_EXPORT int sim_out_get(void *config, void *dims, sim_out *out, const char *field, void *value); - -/* opts */ -// -ACADOS_SYMBOL_EXPORT void *sim_opts_create(sim_config *config, void *dims); -// -ACADOS_SYMBOL_EXPORT void sim_opts_destroy(void *opts); -// -ACADOS_SYMBOL_EXPORT void sim_opts_set(sim_config *config, void *opts, const char *field, void *value); -// -ACADOS_SYMBOL_EXPORT void sim_opts_get(sim_config *config, void *opts, const char *field, void *value); - -/* solver */ -// -ACADOS_SYMBOL_EXPORT acados_size_t sim_calculate_size(sim_config *config, void *dims, void *opts_); -// -ACADOS_SYMBOL_EXPORT sim_solver *sim_assign(sim_config *config, void *dims, void *opts_, void *raw_memory); -// -ACADOS_SYMBOL_EXPORT sim_solver *sim_solver_create(sim_config *config, void *dims, void *opts_); -// -ACADOS_SYMBOL_EXPORT void sim_solver_destroy(void *solver); -// -ACADOS_SYMBOL_EXPORT int sim_solve(sim_solver *solver, sim_in *in, sim_out *out); -// -ACADOS_SYMBOL_EXPORT int sim_precompute(sim_solver *solver, sim_in *in, sim_out *out); -// -ACADOS_SYMBOL_EXPORT int sim_solver_set(sim_solver *solver, const char *field, void *value); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // INTERFACES_ACADOS_C_SIM_INTERFACE_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo.h b/third_party/acados/include/blasfeo/include/blasfeo.h deleted file mode 100644 index c854918193..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo.h +++ /dev/null @@ -1,52 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#include "blasfeo_processor_features.h" -#include "blasfeo_target.h" -#include "blasfeo_block_size.h" -#include "blasfeo_stdlib.h" -#include "blasfeo_common.h" -#include "blasfeo_d_aux.h" -#include "blasfeo_d_aux_ext_dep.h" -#include "blasfeo_d_kernel.h" -#include "blasfeo_d_blas.h" -#include "blasfeo_s_aux.h" -#include "blasfeo_s_aux_ext_dep.h" -#include "blasfeo_s_kernel.h" -#include "blasfeo_s_blas.h" -#include "blasfeo_i_aux_ext_dep.h" -#include "blasfeo_v_aux_ext_dep.h" -#include "blasfeo_timing.h" -#include "blasfeo_memory.h" diff --git a/third_party/acados/include/blasfeo/include/blasfeo_block_size.h b/third_party/acados/include/blasfeo/include/blasfeo_block_size.h deleted file mode 100644 index 5d0907a61c..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_block_size.h +++ /dev/null @@ -1,447 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_BLOCK_SIZE_H_ -#define BLASFEO_BLOCK_SIZE_H_ - - - -#define D_EL_SIZE 8 // double precision -#define S_EL_SIZE 4 // single precision - - - -#if defined( TARGET_X64_INTEL_SKYLAKE_X ) -// common -#define CACHE_LINE_SIZE 64 // data cache size: 64 bytes -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 kB, 8-way -#define L2_CACHE_SIZE (256*1024) //(1024*1024) // L2 data cache size: 1 MB ; DTLB1 64*4 kB = 256 kB -#define LLC_CACHE_SIZE (6*1024*1024) //(8*1024*1024) // LLC cache size: 8 MB ; TLB 1536*4 kB = 6 MB -// double -#define D_PS 8 // panel size -#define D_PLD 8 // 4 // GCD of panel length -#define D_M_KERNEL 24 // max kernel size -#define D_N_KERNEL 8 // max kernel size -#define D_KC 128 //256 // 192 -#define D_NC 144 //72 //96 //72 // 120 // 512 -#define D_MC 2400 // 6000 -// single -#define S_PS 16 // panel size -#define S_PLD 4 // GCD of panel length TODO probably 16 when writing assebly -#define S_M_KERNEL 32 // max kernel size -#define S_N_KERNEL 8 // max kernel size -#define S_KC 128 //256 -#define S_NC 128 //144 -#define S_MC 3000 - -#elif defined( TARGET_X64_INTEL_HASWELL ) -// common -#define CACHE_LINE_SIZE 64 // data cache size: 64 bytes -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 kB, 8-way -#define L2_CACHE_SIZE (256*1024) // L2 data cache size: 256 kB ; DTLB1 64*4 kB = 256 kB -#define LLC_CACHE_SIZE (6*1024*1024) // LLC cache size: 6 MB ; TLB 1024*4 kB = 4 MB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 12 // max kernel size -#define D_N_KERNEL 8 // max kernel size -#define D_KC 256 // 192 -#define D_NC 64 //96 //72 // 120 // 512 -#define D_MC 1500 -// single -#define S_PS 8 // panel size -#define S_PLD 4 // 2 // GCD of panel length -#define S_M_KERNEL 24 // max kernel size -#define S_N_KERNEL 8 // max kernel size -#define S_KC 256 -#define S_NC 144 -#define S_MC 3000 - -#elif defined( TARGET_X64_INTEL_SANDY_BRIDGE ) -// common -#define CACHE_LINE_SIZE 64 // data cache size: 64 bytes -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 kB, 8-way -#define L2_CACHE_SIZE (256*1024) // L2 data cache size: 256 kB ; DTLB1 64*4 kB = 256 kB -#define LLC_CACHE_SIZE (4*1024*1024) // LLC cache size: 4 MB ; TLB 1024*4 kB = 4 MB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 8 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 256 //320 //256 //320 -#define D_NC 72 //64 //72 //60 // 120 -#define D_MC 1000 // 800 -// single -#define S_PS 8 // panel size -#define S_PLD 4 // 2 // GCD of panel length -#define S_M_KERNEL 16 // max kernel size -#define S_N_KERNEL 8 // max kernel size -#define S_KC 256 -#define S_NC 144 -#define S_MC 2000 - -#elif defined( TARGET_X64_INTEL_CORE ) -// common -#define CACHE_LINE_SIZE 64 -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 kB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 4 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 256 -#define D_NC 128 // TODO these are just dummy -#define D_MC 3000 // TODO these are just dummy -// single -#define S_PS 4 -#define S_PLD 4 //2 -#define S_M_KERNEL 4 // max kernel size -#define S_N_KERNEL 4 // max kernel size -#define S_KC 256 -#define S_NC 128 // TODO these are just dummy -#define S_MC 3000 // TODO these are just dummy - -#elif defined( TARGET_X64_AMD_BULLDOZER ) -// common -#define CACHE_LINE_SIZE 64 -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 kB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 4 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 256 -#define D_NC 128 // TODO these are just dummy -#define D_MC 3000 // TODO these are just dummy -// single -#define S_PS 4 -#define S_PLD 4 //2 -#define S_M_KERNEL 4 // max kernel size -#define S_N_KERNEL 4 // max kernel size -#define S_KC 256 -#define S_NC 128 // TODO these are just dummy -#define S_MC 3000 // TODO these are just dummy - - -#elif defined( TARGET_X86_AMD_JAGUAR ) -// common -#define CACHE_LINE_SIZE 64 -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 kB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 4 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 256 -#define D_NC 128 // TODO these are just dummy -#define D_MC 3000 // TODO these are just dummy -// single -#define S_PS 4 -#define S_PLD 4 //2 -#define S_M_KERNEL 4 // max kernel size -#define S_N_KERNEL 4 // max kernel size -#define S_KC 256 -#define S_NC 128 // TODO these are just dummy -#define S_MC 3000 // TODO these are just dummy - - -#elif defined( TARGET_X86_AMD_BARCELONA ) -// common -#define CACHE_LINE_SIZE 64 -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 kB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 4 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 256 -#define D_NC 128 // TODO these are just dummy -#define D_MC 3000 // TODO these are just dummy -// single -#define S_PS 4 -#define S_PLD 4 //2 -#define S_M_KERNEL 4 // max kernel size -#define S_N_KERNEL 4 // max kernel size -#define S_KC 256 -#define S_NC 128 // TODO these are just dummy -#define S_MC 3000 // TODO these are just dummy - - -#elif defined(TARGET_ARMV8A_APPLE_M1) -// common -#define CACHE_LINE_SIZE 64 -#define L1_CACHE_SIZE (128*1024) // L1 data cache size (big cores): 64 kB, ?-way ; DTLB1 ? -#define LLC_CACHE_SIZE (12*1024*1024) // LLC (L2) cache size (big cores): 12 MB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 8 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 512 //256 -#define D_NC 128 //256 -#define D_MC 6000 -// single -#define S_PS 4 -#define S_PLD 4 //2 -#define S_M_KERNEL 8 // max kernel size -#define S_N_KERNEL 8 // max kernel size -#define S_KC 512 -#define S_NC 256 -#define S_MC 6000 - - -#elif defined(TARGET_ARMV8A_ARM_CORTEX_A76) -// common -#define CACHE_LINE_SIZE 64 -#define L1_CACHE_SIZE (64*1024) // L1 data cache size: 64 kB, 4-way ; DTLB1 48*4 kB = 192 kB -#define LLC_CACHE_SIZE (1*1024*1024) // LLC cache size: 1 MB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 8 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 512 //256 -#define D_NC 128 //256 -#define D_MC 6000 -// single -#define S_PS 4 -#define S_PLD 4 //2 -#define S_M_KERNEL 8 // max kernel size -#define S_N_KERNEL 8 // max kernel size -#define S_KC 512 -#define S_NC 256 -#define S_MC 6000 - - -#elif defined(TARGET_ARMV8A_ARM_CORTEX_A73) -// common -#define CACHE_LINE_SIZE 64 -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 (64?) kB, 4-way, seen as 8-(16-)way ; DTLB1 48*4 kB = 192 kB -#define LLC_CACHE_SIZE (1*1024*1024) // LLC cache size: 1 MB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 8 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 320 -#define D_NC 256 -#define D_MC 6000 -// single -#define S_PS 4 -#define S_PLD 4 //2 -#define S_M_KERNEL 8 // max kernel size -#define S_N_KERNEL 8 // max kernel size -#define S_KC 256 -#define S_NC 128 // TODO these are just dummy -#define S_MC 3000 // TODO these are just dummy - - -#elif defined(TARGET_ARMV8A_ARM_CORTEX_A57) -// common -#define CACHE_LINE_SIZE 64 -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 kB, 2-way ; DTLB1 32*4 kB = 128 kB -#define LLC_CACHE_SIZE (1*1024*1024) // LLC cache size: 1 MB // 2 MB ??? -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 8 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 128 //224 //256 //192 -#define D_NC 72 //40 //36 //48 -#define D_MC (4*192) //512 //488 //600 -// single -#define S_PS 4 -#define S_PLD 4 //2 -#define S_M_KERNEL 8 // max kernel size -#define S_N_KERNEL 8 // max kernel size -#define S_KC 256 -#define S_NC 128 // TODO these are just dummy -#define S_MC 3000 // TODO these are just dummy - - -#elif defined(TARGET_ARMV8A_ARM_CORTEX_A55) -// common -#define CACHE_LINE_SIZE 64 -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 kB, 4-way ; DTLB1 16*4 kB = 64 kB -#define LLC_CACHE_SIZE (512*1024) // LLC cache size: 512 kB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 12 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 224 -#define D_NC 160 -#define D_MC 6000 -// single -#define S_PS 4 -#define S_PLD 4 //2 -#define S_M_KERNEL 8 // max kernel size -#define S_N_KERNEL 8 // max kernel size -#define S_KC 256 -#define S_NC 128 // TODO these are just dummy -#define S_MC 3000 // TODO these are just dummy - - -#elif defined(TARGET_ARMV8A_ARM_CORTEX_A53) -// common -#define CACHE_LINE_SIZE 64 -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 kB, 4-way ??? ; DTLB1 10*4 kB = 40 kB -#define LLC_CACHE_SIZE (256*1024) // LLC cache size: 256 kB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 12 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 160 -#define D_NC 128 -#define D_MC 6000 -// single -#define S_PS 4 -#define S_PLD 4 //2 -#define S_M_KERNEL 8 // max kernel size -#define S_N_KERNEL 8 // max kernel size -#define S_KC 256 -#define S_NC 128 // TODO these are just dummy -#define S_MC 3000 // TODO these are just dummy - - -#elif defined( TARGET_ARMV7A_ARM_CORTEX_A15 ) -// common -#define CACHE_LINE_SIZE 64 -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 kB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 4 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 256 -#define D_NC 128 // TODO these are just dummy -#define D_MC 3000 // TODO these are just dummy -// single -#define S_PS 4 -#define S_PLD 4 //2 -#define S_M_KERNEL 4 // max kernel size -#define S_N_KERNEL 4 // max kernel size -#define S_KC 256 -#define S_NC 128 // TODO these are just dummy -#define S_MC 3000 // TODO these are just dummy - - -#elif defined( TARGET_ARMV7A_ARM_CORTEX_A7 ) -// common -#define CACHE_LINE_SIZE 64 -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 kB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 4 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 256 -#define D_NC 128 // TODO these are just dummy -#define D_MC 3000 // TODO these are just dummy -// single -#define S_PS 4 -#define S_PLD 4 //2 -#define S_M_KERNEL 4 // max kernel size -#define S_N_KERNEL 4 // max kernel size -#define S_KC 256 -#define S_NC 128 // TODO these are just dummy -#define S_MC 3000 // TODO these are just dummy - - -#elif defined( TARGET_ARMV7A_ARM_CORTEX_A9 ) -// common -#define CACHE_LINE_SIZE 32 -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 kB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 4 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 256 -#define D_NC 128 // TODO these are just dummy -#define D_MC 3000 // TODO these are just dummy -// single -#define S_PS 4 -#define S_PLD 4 //2 -#define S_M_KERNEL 4 // max kernel size -#define S_N_KERNEL 4 // max kernel size -#define S_KC 256 -#define S_NC 128 // TODO these are just dummy -#define S_MC 3000 // TODO these are just dummy - - -#elif defined( TARGET_GENERIC ) -// common -#define CACHE_LINE_SIZE 64 -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 kB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 4 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 256 -#define D_NC 128 // TODO these are just dummy -#define D_MC 3000 // TODO these are just dummy - -// single -#define S_PS 4 -#define S_PLD 4 //2 -#define S_M_KERNEL 4 // max kernel size -#define S_N_KERNEL 4 // max kernel size -#define S_KC 256 -#define S_NC 128 // TODO these are just dummy -#define S_MC 3000 // TODO these are just dummy - - -#else -#error "Unknown architecture" -#endif - - - -#define D_CACHE_LINE_EL (CACHE_LINE_SIZE/D_EL_SIZE) -#define D_L1_CACHE_EL (L1_CACHE_SIZE/D_EL_SIZE) -#define D_L2_CACHE_EL (L2_CACHE_SIZE/D_EL_SIZE) -#define D_LLC_CACHE_EL (LLC_CACHE_SIZE/D_EL_SIZE) - -#define S_CACHE_LINE_EL (CACHE_LINE_SIZE/S_EL_SIZE) -#define S_L1_CACHE_EL (L1_CACHE_SIZE/S_EL_SIZE) -#define S_L2_CACHE_EL (L2_CACHE_SIZE/S_EL_SIZE) -#define S_LLC_CACHE_EL (LLC_CACHE_SIZE/S_EL_SIZE) - - - -#endif // BLASFEO_BLOCK_SIZE_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_common.h b/third_party/acados/include/blasfeo/include/blasfeo_common.h deleted file mode 100644 index 03b6c36d84..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_common.h +++ /dev/null @@ -1,274 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_COMMON_H_ -#define BLASFEO_COMMON_H_ - - - -#include "blasfeo_target.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -#if defined(__GNUC__) || defined(__clang__) || defined(__INTEL_COMPILER) || defined(__ICL) || defined(__ICC) || defined(__INTEL_LLVM_COMPILER) -#define ALIGNED(VEC, BYTES) VEC __attribute__ ((aligned ( BYTES ))) -#elif defined (_MSC_VER) -#define ALIGNED(VEC, BYTES) __declspec(align( BYTES )) VEC -#else -#define ALIGNED(VEC, BYTES) VEC -#endif - - - - -#if ( defined(LA_HIGH_PERFORMANCE) & defined(MF_PANELMAJ) ) | ( defined(LA_REFERENCE) & defined(MF_PANELMAJ) ) - -#include "blasfeo_block_size.h" - -// matrix structure -struct blasfeo_dmat - { - double *mem; // pointer to passed chunk of memory - double *pA; // pointer to a pm*pn array of doubles, the first is aligned to cache line size - double *dA; // pointer to a min(m,n) (or max???) array of doubles - int m; // rows - int n; // cols - int pm; // packed number or rows - int cn; // packed number or cols - int use_dA; // flag to tell if dA can be used - int memsize; // size of needed memory - }; - -struct blasfeo_smat - { - float *mem; // pointer to passed chunk of memory - float *pA; // pointer to a pm*pn array of floats, the first is aligned to cache line size - float *dA; // pointer to a min(m,n) (or max???) array of floats - int m; // rows - int n; // cols - int pm; // packed number or rows - int cn; // packed number or cols - int use_dA; // flag to tell if dA can be used - int memsize; // size of needed memory - }; - -// vector structure -struct blasfeo_dvec - { - double *mem; // pointer to passed chunk of memory - double *pa; // pointer to a pm array of doubles, the first is aligned to cache line size - int m; // size - int pm; // packed size - int memsize; // size of needed memory - }; - -struct blasfeo_svec - { - float *mem; // pointer to passed chunk of memory - float *pa; // pointer to a pm array of floats, the first is aligned to cache line size - int m; // size - int pm; // packed size - int memsize; // size of needed memory - }; - -#define BLASFEO_DMATEL(sA,ai,aj) ((sA)->pA[((ai)-((ai)&(D_PS-1)))*(sA)->cn+(aj)*D_PS+((ai)&(D_PS-1))]) -#define BLASFEO_SMATEL(sA,ai,aj) ((sA)->pA[((ai)-((ai)&(S_PS-1)))*(sA)->cn+(aj)*S_PS+((ai)&(S_PS-1))]) -#define BLASFEO_DVECEL(sa,ai) ((sa)->pa[ai]) -#define BLASFEO_SVECEL(sa,ai) ((sa)->pa[ai]) - -#elif ( defined(LA_HIGH_PERFORMANCE) & defined(MF_COLMAJ) ) | ( defined(LA_REFERENCE) & defined(MF_COLMAJ) ) | defined(LA_EXTERNAL_BLAS_WRAPPER) - -// matrix structure -struct blasfeo_dmat - { - double *mem; // pointer to passed chunk of memory - double *pA; // pointer to a m*n array of doubles - double *dA; // pointer to a min(m,n) (or max???) array of doubles - int m; // rows - int n; // cols - int use_dA; // flag to tell if dA can be used - int memsize; // size of needed memory - }; - -struct blasfeo_smat - { - float *mem; // pointer to passed chunk of memory - float *pA; // pointer to a m*n array of floats - float *dA; // pointer to a min(m,n) (or max???) array of floats - int m; // rows - int n; // cols - int use_dA; // flag to tell if dA can be used - int memsize; // size of needed memory - }; - -// vector structure -struct blasfeo_dvec - { - double *mem; // pointer to passed chunk of memory - double *pa; // pointer to a m array of doubles, the first is aligned to cache line size - int m; // size - int memsize; // size of needed memory - }; - -struct blasfeo_svec - { - float *mem; // pointer to passed chunk of memory - float *pa; // pointer to a m array of floats, the first is aligned to cache line size - int m; // size - int memsize; // size of needed memory - }; - -#define BLASFEO_DMATEL(sA,ai,aj) ((sA)->pA[(ai)+(aj)*(sA)->m]) -#define BLASFEO_SMATEL(sA,ai,aj) ((sA)->pA[(ai)+(aj)*(sA)->m]) -#define BLASFEO_DVECEL(sa,ai) ((sa)->pa[ai]) -#define BLASFEO_SVECEL(sa,ai) ((sa)->pa[ai]) - -#else - -#error : wrong LA or MF choice - -#endif - - - -// Explicitly panel-major matrix structure -struct blasfeo_pm_dmat - { - double *mem; // pointer to passed chunk of memory - double *pA; // pointer to a pm*pn array of doubles, the first is aligned to cache line size - double *dA; // pointer to a min(m,n) (or max???) array of doubles - int m; // rows - int n; // cols - int pm; // packed number or rows - int cn; // packed number or cols - int use_dA; // flag to tell if dA can be used - int ps; // panel size - int memsize; // size of needed memory - }; - -struct blasfeo_pm_smat - { - float *mem; // pointer to passed chunk of memory - float *pA; // pointer to a pm*pn array of floats, the first is aligned to cache line size - float *dA; // pointer to a min(m,n) (or max???) array of floats - int m; // rows - int n; // cols - int pm; // packed number or rows - int cn; // packed number or cols - int use_dA; // flag to tell if dA can be used - int ps; // panel size - int memsize; // size of needed memory - }; - -struct blasfeo_pm_dvec - { - double *mem; // pointer to passed chunk of memory - double *pa; // pointer to a pm array of doubles, the first is aligned to cache line size - int m; // size - int pm; // packed size - int memsize; // size of needed memory - }; - -struct blasfeo_pm_svec - { - float *mem; // pointer to passed chunk of memory - float *pa; // pointer to a pm array of floats, the first is aligned to cache line size - int m; // size - int pm; // packed size - int memsize; // size of needed memory - }; - -// Explicitly column-major matrix structure -struct blasfeo_cm_dmat - { - double *mem; // pointer to passed chunk of memory - double *pA; // pointer to a m*n array of doubles - double *dA; // pointer to a min(m,n) (or max???) array of doubles - int m; // rows - int n; // cols - int use_dA; // flag to tell if dA can be used - int memsize; // size of needed memory - }; - -struct blasfeo_cm_smat - { - float *mem; // pointer to passed chunk of memory - float *pA; // pointer to a m*n array of floats - float *dA; // pointer to a min(m,n) (or max???) array of floats - int m; // rows - int n; // cols - int use_dA; // flag to tell if dA can be used - int memsize; // size of needed memory - }; - -struct blasfeo_cm_dvec - { - double *mem; // pointer to passed chunk of memory - double *pa; // pointer to a m array of doubles, the first is aligned to cache line size - int m; // size - int memsize; // size of needed memory - }; - -struct blasfeo_cm_svec - { - float *mem; // pointer to passed chunk of memory - float *pa; // pointer to a m array of floats, the first is aligned to cache line size - int m; // size - int memsize; // size of needed memory - }; - - -#define BLASFEO_PM_DMATEL(sA,ai,aj) ((sA)->pA[((ai)-((ai)&((sA)->ps-1)))*(sA)->cn+(aj)*((sA)->ps)+((ai)&((sA)->ps-1))]) -#define BLASFEO_PM_SMATEL(sA,ai,aj) ((sA)->pA[((ai)-((ai)&((sA)->ps-1)))*(sA)->cn+(aj)*((sA)->ps)+((ai)&((sA)->ps-1))]) -#define BLASFEO_PM_DVECEL(sa,ai) ((sa)->pa[ai]) -#define BLASFEO_PM_SVECEL(sa,ai) ((sa)->pa[ai]) -#define BLASFEO_CM_DMATEL(sA,ai,aj) ((sA)->pA[(ai)+(aj)*(sA)->m]) -#define BLASFEO_CM_SMATEL(sA,ai,aj) ((sA)->pA[(ai)+(aj)*(sA)->m]) -#define BLASFEO_CM_DVECEL(sa,ai) ((sa)->pa[ai]) -#define BLASFEO_CM_SVECEL(sa,ai) ((sa)->pa[ai]) - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_COMMON_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_d_aux.h b/third_party/acados/include/blasfeo/include/blasfeo_d_aux.h deleted file mode 100644 index a6d6119c6c..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_d_aux.h +++ /dev/null @@ -1,255 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -/* - * auxiliary algebra operations header - * - * include/blasfeo_aux_lib*.h - * - */ - -#ifndef BLASFEO_D_AUX_H_ -#define BLASFEO_D_AUX_H_ - - - -#include - -#include "blasfeo_common.h" -#include "blasfeo_d_aux_old.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - -// --- memory size calculations -// -// returns the memory size (in bytes) needed for a dmat -size_t blasfeo_memsize_dmat(int m, int n); -// returns the memory size (in bytes) needed for the diagonal of a dmat -size_t blasfeo_memsize_diag_dmat(int m, int n); -// returns the memory size (in bytes) needed for a dvec -size_t blasfeo_memsize_dvec(int m); - -// --- creation -// -// create a strmat for a matrix of size m*n by using memory passed by a pointer (pointer is not updated) -void blasfeo_create_dmat(int m, int n, struct blasfeo_dmat *sA, void *memory); -// create a strvec for a vector of size m by using memory passed by a pointer (pointer is not updated) -void blasfeo_create_dvec(int m, struct blasfeo_dvec *sA, void *memory); - -// --- packing -// pack the column-major matrix A into the matrix struct B -void blasfeo_pack_dmat(int m, int n, double *A, int lda, struct blasfeo_dmat *sB, int bi, int bj); -// pack the lower-triangular column-major matrix A into the matrix struct B -void blasfeo_pack_l_dmat(int m, int n, double *A, int lda, struct blasfeo_dmat *sB, int bi, int bj); -// pack the upper-triangular column-major matrix A into the matrix struct B -void blasfeo_pack_u_dmat(int m, int n, double *A, int lda, struct blasfeo_dmat *sB, int bi, int bj); -// transpose and pack the column-major matrix A into the matrix struct B -void blasfeo_pack_tran_dmat(int m, int n, double *A, int lda, struct blasfeo_dmat *sB, int bi, int bj); -// pack the vector x into the vector structure y -void blasfeo_pack_dvec(int m, double *x, int xi, struct blasfeo_dvec *sy, int yi); -// unpack the matrix structure A into the column-major matrix B -void blasfeo_unpack_dmat(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, double *B, int ldb); -// transpose and unpack the matrix structure A into the column-major matrix B -void blasfeo_unpack_tran_dmat(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, double *B, int ldb); -// pack the vector structure x into the vector y -void blasfeo_unpack_dvec(int m, struct blasfeo_dvec *sx, int xi, double *y, int yi); - -// --- cast -// -//void d_cast_mat2strmat(double *A, struct blasfeo_dmat *sA); // TODO -//void d_cast_diag_mat2strmat(double *dA, struct blasfeo_dmat *sA); // TODO -//void d_cast_vec2vecmat(double *a, struct blasfeo_dvec *sx); // TODO - - -// ge -// --- insert/extract -// -// sA[ai, aj] <= a -void blasfeo_dgein1(double a, struct blasfeo_dmat *sA, int ai, int aj); -// <= sA[ai, aj] -double blasfeo_dgeex1(struct blasfeo_dmat *sA, int ai, int aj); - -// --- set -// A <= alpha -void blasfeo_dgese(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj); - -// --- copy / scale -// B <= A -void blasfeo_dgecp(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); -// A <= alpha*A -void blasfeo_dgesc(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj); -// B <= alpha*A -void blasfeo_dgecpsc(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); -// B <= A, A lower triangular -void blasfeo_dtrcp_l(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); -void blasfeo_dtrcpsc_l(int m, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); -void blasfeo_dtrsc_l(int m, double alpha, struct blasfeo_dmat *sA, int ai, int aj); - -// --- sum -// B <= B + alpha*A -void blasfeo_dgead(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); -// y <= y + alpha*x -void blasfeo_dvecad(int m, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi); - -// --- traspositions -// B <= A' -void blasfeo_dgetr(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); -// B <= A', A lower triangular -void blasfeo_dtrtr_l(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); -// B <= A', A upper triangular -void blasfeo_dtrtr_u(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); - -// dia -// diag(A) += alpha -void blasfeo_ddiare(int kmax, double alpha, struct blasfeo_dmat *sA, int ai, int aj); -// diag(A) <= alpha*x -void blasfeo_ddiain(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -// diag(A)[idx] <= alpha*x -void blasfeo_ddiain_sp(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dmat *sD, int di, int dj); -// x <= diag(A) -void blasfeo_ddiaex(int kmax, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi); -// x <= diag(A)[idx] -void blasfeo_ddiaex_sp(int kmax, double alpha, int *idx, struct blasfeo_dmat *sD, int di, int dj, struct blasfeo_dvec *sx, int xi); -// diag(A) += alpha*x -void blasfeo_ddiaad(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -// diag(A)[idx] += alpha*x -void blasfeo_ddiaad_sp(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dmat *sD, int di, int dj); -// diag(A)[idx] = y + alpha*x -void blasfeo_ddiaadin_sp(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi, int *idx, struct blasfeo_dmat *sD, int di, int dj); - -// row -void blasfeo_drowin(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -void blasfeo_drowex(int kmax, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi); -void blasfeo_drowad(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -void blasfeo_drowad_sp(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dmat *sD, int di, int dj); -void blasfeo_drowsw(int kmax, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sC, int ci, int cj); -void blasfeo_drowpe(int kmax, int *ipiv, struct blasfeo_dmat *sA); -void blasfeo_drowpei(int kmax, int *ipiv, struct blasfeo_dmat *sA); - -// col -void blasfeo_dcolex(int kmax, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi); -void blasfeo_dcolin(int kmax, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -void blasfeo_dcolad(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -void blasfeo_dcolsc(int kmax, double alpha, struct blasfeo_dmat *sA, int ai, int aj); -void blasfeo_dcolsw(int kmax, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sC, int ci, int cj); -void blasfeo_dcolpe(int kmax, int *ipiv, struct blasfeo_dmat *sA); -void blasfeo_dcolpei(int kmax, int *ipiv, struct blasfeo_dmat *sA); - -// vec -// a <= alpha -void blasfeo_dvecse(int m, double alpha, struct blasfeo_dvec *sx, int xi); -// sx[xi] <= a -void blasfeo_dvecin1(double a, struct blasfeo_dvec *sx, int xi); -// <= sx[xi] -double blasfeo_dvecex1(struct blasfeo_dvec *sx, int xi); -// y <= x -void blasfeo_dveccp(int m, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi); -// x <= alpha*x -void blasfeo_dvecsc(int m, double alpha, struct blasfeo_dvec *sx, int xi); -// y <= alpha*x -void blasfeo_dveccpsc(int m, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi); -// z[idx] += alpha * x -void blasfeo_dvecad_sp(int m, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dvec *sz, int zi); -// z[idx] <= alpha * x -void blasfeo_dvecin_sp(int m, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dvec *sz, int zi); -// z <= alpha * x[idx] -void blasfeo_dvecex_sp(int m, double alpha, int *idx, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z += alpha * x[idx] -void blasfeo_dvecexad_sp(int m, double alpha, int *idx, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); - -void blasfeo_dveccl(int m, - struct blasfeo_dvec *sxm, int xim, struct blasfeo_dvec *sx, int xi, - struct blasfeo_dvec *sxp, int xip, struct blasfeo_dvec *sz, int zi); - -void blasfeo_dveccl_mask(int m, - struct blasfeo_dvec *sxm, int xim, struct blasfeo_dvec *sx, int xi, - struct blasfeo_dvec *sxp, int xip, struct blasfeo_dvec *sz, int zi, - struct blasfeo_dvec *sm, int mi); - -void blasfeo_dvecze(int m, struct blasfeo_dvec *sm, int mi, struct blasfeo_dvec *sv, int vi, struct blasfeo_dvec *se, int ei); -void blasfeo_dvecnrm_inf(int m, struct blasfeo_dvec *sx, int xi, double *ptr_norm); -void blasfeo_dvecnrm_2(int m, struct blasfeo_dvec *sx, int xi, double *ptr_norm); -void blasfeo_dvecpe(int kmax, int *ipiv, struct blasfeo_dvec *sx, int xi); -void blasfeo_dvecpei(int kmax, int *ipiv, struct blasfeo_dvec *sx, int xi); - - - - - -/* -* Explicitly panel-major matrix format -*/ - -// returns the memory size (in bytes) needed for a dmat -size_t blasfeo_pm_memsize_dmat(int ps, int m, int n); -// create a strmat for a matrix of size m*n by using memory passed by a pointer (pointer is not updated) -void blasfeo_pm_create_dmat(int ps, int m, int n, struct blasfeo_pm_dmat *sA, void *memory); -// print -void blasfeo_pm_print_dmat(int m, int n, struct blasfeo_pm_dmat *sA, int ai, int aj); - - - -/* -* Explicitly panel-major matrix format -*/ - -// returns the memory size (in bytes) needed for a dmat -size_t blasfeo_cm_memsize_dmat(int m, int n); -// create a strmat for a matrix of size m*n by using memory passed by a pointer (pointer is not updated) -void blasfeo_cm_create_dmat(int m, int n, struct blasfeo_pm_dmat *sA, void *memory); - - - -// -// BLAS API helper functions -// - -#if ( defined(BLAS_API) & defined(MF_PANELMAJ) ) -// aux -void blasfeo_cm_dgetr(int m, int n, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj); -#endif - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_D_AUX_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_d_aux_ext_dep.h b/third_party/acados/include/blasfeo/include/blasfeo_d_aux_ext_dep.h deleted file mode 100644 index bee9e986f1..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_d_aux_ext_dep.h +++ /dev/null @@ -1,145 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -/* - * auxiliary algebra operation external dependancies header - * - * include/blasfeo_d_aux_ext_dep.h - * - * - dynamic memory allocation - * - print - * - */ - -#ifndef BLASFEO_D_AUX_EXT_DEP_H_ -#define BLASFEO_D_AUX_EXT_DEP_H_ - - - -#include - - - -#include "blasfeo_common.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -#ifdef EXT_DEP - -/* column-major matrices */ - -// dynamically allocate row*col doubles of memory and set accordingly a pointer to double; set allocated memory to zero -void d_zeros(double **pA, int row, int col); -// dynamically allocate row*col doubles of memory aligned to 64-byte boundaries and set accordingly a pointer to double; set allocated memory to zero -void d_zeros_align(double **pA, int row, int col); -// dynamically allocate size bytes of memory aligned to 64-byte boundaries and set accordingly a pointer to double; set allocated memory to zero -void d_zeros_align_bytes(double **pA, int size); -// free the memory allocated by d_zeros -void d_free(double *pA); -// free the memory allocated by d_zeros_align or d_zeros_align_bytes -void d_free_align(double *pA); -// print a column-major matrix -void d_print_mat(int m, int n, double *A, int lda); -// print the transposed of a column-major matrix -void d_print_tran_mat(int row, int col, double *A, int lda); -// print to file a column-major matrix -void d_print_to_file_mat(FILE *file, int row, int col, double *A, int lda); -// print to file a column-major matrix in exponential format -void d_print_to_file_exp_mat(FILE *file, int row, int col, double *A, int lda); -// print to string a column-major matrix -void d_print_to_string_mat(char **buf_out, int row, int col, double *A, int lda); -// print to file the transposed of a column-major matrix -void d_print_tran_to_file_mat(FILE *file, int row, int col, double *A, int lda); -// print to file the transposed of a column-major matrix in exponential format -void d_print_tran_to_file_exp_mat(FILE *file, int row, int col, double *A, int lda); -// print in exponential notation a column-major matrix -void d_print_exp_mat(int m, int n, double *A, int lda); -// print in exponential notation the transposed of a column-major matrix -void d_print_exp_tran_mat(int row, int col, double *A, int lda); - -/* strmat and strvec */ - -// create a strmat for a matrix of size m*n by dynamically allocating memory -void blasfeo_allocate_dmat(int m, int n, struct blasfeo_dmat *sA); -// create a strvec for a vector of size m by dynamically allocating memory -void blasfeo_allocate_dvec(int m, struct blasfeo_dvec *sa); -// free the memory allocated by blasfeo_allocate_dmat -void blasfeo_free_dmat(struct blasfeo_dmat *sA); -// free the memory allocated by blasfeo_allocate_dvec -void blasfeo_free_dvec(struct blasfeo_dvec *sa); -// print a strmat -void blasfeo_print_dmat(int m, int n, struct blasfeo_dmat *sA, int ai, int aj); -// print in exponential notation a strmat -void blasfeo_print_exp_dmat(int m, int n, struct blasfeo_dmat *sA, int ai, int aj); -// print to file a strmat -void blasfeo_print_to_file_dmat(FILE *file, int m, int n, struct blasfeo_dmat *sA, int ai, int aj); -// print to file a strmat in exponential format -void blasfeo_print_to_file_exp_dmat(FILE *file, int m, int n, struct blasfeo_dmat *sA, int ai, int aj); -// print to string a strmat -void blasfeo_print_to_string_dmat(char **buf_out, int m, int n, struct blasfeo_dmat *sA, int ai, int aj); -// print the transposed of a strmat -void blasfeo_print_tran_dmat(int m, int n, struct blasfeo_dmat *sA, int ai, int aj); -// print a strvec -void blasfeo_print_dvec(int m, struct blasfeo_dvec *sa, int ai); -// print in exponential notation a strvec -void blasfeo_print_exp_dvec(int m, struct blasfeo_dvec *sa, int ai); -// print to file a strvec -void blasfeo_print_to_file_dvec(FILE *file, int m, struct blasfeo_dvec *sa, int ai); -// print to string a strvec -void blasfeo_print_to_string_dvec(char **buf_out, int m, struct blasfeo_dvec *sa, int ai); -// print the transposed of a strvec -void blasfeo_print_tran_dvec(int m, struct blasfeo_dvec *sa, int ai); -// print in exponential notation the transposed of a strvec -void blasfeo_print_exp_tran_dvec(int m, struct blasfeo_dvec *sa, int ai); -// print to file the transposed of a strvec -void blasfeo_print_to_file_tran_dvec(FILE *file, int m, struct blasfeo_dvec *sa, int ai); -// print to string the transposed of a strvec -void blasfeo_print_to_string_tran_dvec(char **buf_out, int m, struct blasfeo_dvec *sa, int ai); - -#endif // EXT_DEP - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_D_AUX_EXT_DEP_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_d_aux_ext_dep_ref.h b/third_party/acados/include/blasfeo/include/blasfeo_d_aux_ext_dep_ref.h deleted file mode 100644 index 81b811f032..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_d_aux_ext_dep_ref.h +++ /dev/null @@ -1,84 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -/* - * auxiliary algebra operation external dependancies header - * - * include/blasfeo_d_aux_ext_dep.h - * - * - dynamic memory allocation - * - print - * - */ - -#ifndef BLASFEO_D_AUX_EXT_DEP_REF_H_ -#define BLASFEO_D_AUX_EXT_DEP_REF_H_ - - -#include - -#include "blasfeo_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - -// expose reference BLASFEO for testing -// see blasfeo_d_aux_exp_dep.h for help - -void blasfeo_print_dmat_ref(int m, int n, struct blasfeo_dmat_ref *sA, int ai, int aj); -void blasfeo_allocate_dmat_ref(int m, int n, struct blasfeo_dmat_ref *sA); -void blasfeo_allocate_dvec_ref(int m, struct blasfeo_dvec_ref *sa); -void blasfeo_free_dmat_ref(struct blasfeo_dmat_ref *sA); -void blasfeo_free_dvec_ref(struct blasfeo_dvec_ref *sa); -void blasfeo_print_dmat_ref(int m, int n, struct blasfeo_dmat_ref *sA, int ai, int aj); -void blasfeo_print_exp_dmat_ref(int m, int n, struct blasfeo_dmat_ref *sA, int ai, int aj); -void blasfeo_print_to_file_dmat_ref(FILE *file, int m, int n, struct blasfeo_dmat_ref *sA, int ai, int aj); -void blasfeo_print_to_file_exp_dmat_ref(FILE *file, int m, int n, struct blasfeo_dmat_ref *sA, int ai, int aj); -void blasfeo_print_to_string_dmat_ref(char **buf_out, int m, int n, struct blasfeo_dmat_ref *sA, int ai, int aj); -void blasfeo_print_dvec(int m, struct blasfeo_dvec *sa, int ai); -void blasfeo_print_exp_dvec(int m, struct blasfeo_dvec *sa, int ai); -void blasfeo_print_to_file_dvec(FILE *file, int m, struct blasfeo_dvec *sa, int ai); -void blasfeo_print_to_string_dvec(char **buf_out, int m, struct blasfeo_dvec *sa, int ai); -void blasfeo_print_tran_dvec(int m, struct blasfeo_dvec *sa, int ai); -void blasfeo_print_exp_tran_dvec(int m, struct blasfeo_dvec *sa, int ai); -void blasfeo_print_to_file_tran_dvec(FILE *file, int m, struct blasfeo_dvec *sa, int ai); -void blasfeo_print_to_string_tran_dvec(char **buf_out, int m, struct blasfeo_dvec *sa, int ai); - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_D_AUX_EXT_DEP_REF_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_d_aux_old.h b/third_party/acados/include/blasfeo/include/blasfeo_d_aux_old.h deleted file mode 100644 index 3a1847a6a0..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_d_aux_old.h +++ /dev/null @@ -1,75 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -/* - * ----------- TOMOVE - * - * expecting column major matrices - * - */ - -#include "blasfeo_common.h" - - -void dtrcp_l_lib(int m, double alpha, int offsetA, double *A, int sda, int offsetB, double *B, int sdb); -void dgead_lib(int m, int n, double alpha, int offsetA, double *A, int sda, int offsetB, double *B, int sdb); -// TODO remove ??? -void ddiain_sqrt_lib(int kmax, double *x, int offset, double *pD, int sdd); -// TODO ddiaad1 -void ddiareg_lib(int kmax, double reg, int offset, double *pD, int sdd); - - -void dgetr_lib(int m, int n, double alpha, int offsetA, double *pA, int sda, int offsetC, double *pC, int sdc); -void dtrtr_l_lib(int m, double alpha, int offsetA, double *pA, int sda, int offsetC, double *pC, int sdc); -void dtrtr_u_lib(int m, double alpha, int offsetA, double *pA, int sda, int offsetC, double *pC, int sdc); -void ddiaex_lib(int kmax, double alpha, int offset, double *pD, int sdd, double *x); -void ddiaad_lib(int kmax, double alpha, double *x, int offset, double *pD, int sdd); -void ddiain_libsp(int kmax, int *idx, double alpha, double *x, double *pD, int sdd); -void ddiaex_libsp(int kmax, int *idx, double alpha, double *pD, int sdd, double *x); -void ddiaad_libsp(int kmax, int *idx, double alpha, double *x, double *pD, int sdd); -void ddiaadin_libsp(int kmax, int *idx, double alpha, double *x, double *y, double *pD, int sdd); -void drowin_lib(int kmax, double alpha, double *x, double *pD); -void drowex_lib(int kmax, double alpha, double *pD, double *x); -void drowad_lib(int kmax, double alpha, double *x, double *pD); -void drowin_libsp(int kmax, double alpha, int *idx, double *x, double *pD); -void drowad_libsp(int kmax, int *idx, double alpha, double *x, double *pD); -void drowadin_libsp(int kmax, int *idx, double alpha, double *x, double *y, double *pD); -void dcolin_lib(int kmax, double *x, int offset, double *pD, int sdd); -void dcolad_lib(int kmax, double alpha, double *x, int offset, double *pD, int sdd); -void dcolin_libsp(int kmax, int *idx, double *x, double *pD, int sdd); -void dcolad_libsp(int kmax, double alpha, int *idx, double *x, double *pD, int sdd); -void dcolsw_lib(int kmax, int offsetA, double *pA, int sda, int offsetC, double *pC, int sdc); -void dvecin_libsp(int kmax, int *idx, double *x, double *y); -void dvecad_libsp(int kmax, int *idx, double alpha, double *x, double *y); diff --git a/third_party/acados/include/blasfeo/include/blasfeo_d_aux_ref.h b/third_party/acados/include/blasfeo/include/blasfeo_d_aux_ref.h deleted file mode 100644 index 1e007fa89e..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_d_aux_ref.h +++ /dev/null @@ -1,208 +0,0 @@ - -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_D_AUX_REF_H_ -#define BLASFEO_D_AUX_REF_H_ - - - -#include - -#include "blasfeo_common.h" -#include "blasfeo_d_aux_old.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - -// --- memory calculations -// -// returns the memory size (in bytes) needed for a dmat -size_t blasfeo_ref_memsize_dmat(int m, int n); -// returns the memory size (in bytes) needed for the diagonal of a dmat -size_t blasfeo_ref_memsize_diag_dmat(int m, int n); -// returns the memory size (in bytes) needed for a dvec -size_t blasfeo_ref_memsize_dvec(int m); - -// --- creation -// -// create a strmat for a matrix of size m*n by using memory passed by a pointer (pointer is not updated) -void blasfeo_ref_create_dmat(int m, int n, struct blasfeo_dmat *sA, void *memory); -// create a strvec for a vector of size m by using memory passed by a pointer (pointer is not updated) -void blasfeo_ref_create_dvec(int m, struct blasfeo_dvec *sA, void *memory); - -// --- packing -// pack the column-major matrix A into the matrix struct B -void blasfeo_ref_pack_dmat(int m, int n, double *A, int lda, struct blasfeo_dmat *sB, int bi, int bj); -// pack the lower-triangular column-major matrix A into the matrix struct B -void blasfeo_ref_pack_l_dmat(int m, int n, double *A, int lda, struct blasfeo_dmat *sB, int bi, int bj); -// pack the upper-triangular column-major matrix A into the matrix struct B -void blasfeo_ref_pack_u_dmat(int m, int n, double *A, int lda, struct blasfeo_dmat *sB, int bi, int bj); -// transpose and pack the column-major matrix A into the matrix struct B -void blasfeo_ref_pack_tran_dmat(int m, int n, double *A, int lda, struct blasfeo_dmat *sB, int bi, int bj); -// pack the vector x into the vector structure y -void blasfeo_ref_pack_dvec(int m, double *x, int xi, struct blasfeo_dvec *sy, int yi); -// unpack the matrix structure A into the column-major matrix B -void blasfeo_ref_unpack_dmat(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, double *B, int ldb); -// transpose and unpack the matrix structure A into the column-major matrix B -void blasfeo_ref_unpack_tran_dmat(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, double *B, int ldb); -// pack the vector structure x into the vector y -void blasfeo_ref_unpack_dvec(int m, struct blasfeo_dvec *sx, int xi, double *y, int yi); - -// --- cast -// -void ref_d_cast_mat2strmat(double *A, struct blasfeo_dmat *sA); // TODO -void ref_d_cast_diag_mat2strmat(double *dA, struct blasfeo_dmat *sA); // TODO -void ref_d_cast_vec2vecmat(double *a, struct blasfeo_dvec *sx); // TODO - - -// ge -// --- insert/extract -// -// sA[ai, aj] <= a -void blasfeo_ref_dgein1(double a, struct blasfeo_dmat *sA, int ai, int aj); -// <= sA[ai, aj] -double blasfeo_ref_dgeex1(struct blasfeo_dmat *sA, int ai, int aj); - -// --- set -// A <= alpha -void blasfeo_ref_dgese(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj); - -// --- copy / scale -// B <= A -void blasfeo_ref_dgecp(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); -// A <= alpha*A -void blasfeo_ref_dgesc(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj); -// B <= alpha*A -void blasfeo_ref_dgecpsc(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); -// B <= A, A lower triangular -void blasfeo_ref_dtrcp_l(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); -void blasfeo_ref_dtrcpsc_l(int m, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); -void blasfeo_ref_dtrsc_l(int m, double alpha, struct blasfeo_dmat *sA, int ai, int aj); - -// --- sum -// B <= B + alpha*A -void blasfeo_ref_dgead(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sC, int yi, int cj); -// y <= y + alpha*x -void blasfeo_ref_dvecad(int m, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi); - -// --- traspositions -// B <= A' -void blasfeo_ref_dgetr(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); -// B <= A', A lower triangular -void blasfeo_ref_dtrtr_l(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); -// B <= A', A upper triangular -void blasfeo_ref_dtrtr_u(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); - -// dia -// diag(A) += alpha -void blasfeo_ref_ddiare(int kmax, double alpha, struct blasfeo_dmat *sA, int ai, int aj); -// diag(A) <= alpha*x -void blasfeo_ref_ddiain(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -// diag(A)[idx] <= alpha*x -void blasfeo_ref_ddiain_sp(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dmat *sD, int di, int dj); -// x <= diag(A) -void blasfeo_ref_ddiaex(int kmax, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi); -// x <= diag(A)[idx] -void blasfeo_ref_ddiaex_sp(int kmax, double alpha, int *idx, struct blasfeo_dmat *sD, int di, int dj, struct blasfeo_dvec *sx, int xi); -// diag(A) += alpha*x -void blasfeo_ref_ddiaad(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -// diag(A)[idx] += alpha*x -void blasfeo_ref_ddiaad_sp(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dmat *sD, int di, int dj); -// diag(A)[idx] = y + alpha*x -void blasfeo_ref_ddiaadin_sp(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi, int *idx, struct blasfeo_dmat *sD, int di, int dj); - -// row -void blasfeo_ref_drowin(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -void blasfeo_ref_drowex(int kmax, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi); -void blasfeo_ref_drowad(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -void blasfeo_ref_drowad_sp(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dmat *sD, int di, int dj); -void blasfeo_ref_drowsw(int kmax, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sC, int ci, int cj); -void blasfeo_ref_drowpe(int kmax, int *ipiv, struct blasfeo_dmat *sA); -void blasfeo_ref_drowpei(int kmax, int *ipiv, struct blasfeo_dmat *sA); - -// col -void blasfeo_ref_dcolex(int kmax, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi); -void blasfeo_ref_dcolin(int kmax, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -void blasfeo_ref_dcolad(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -void blasfeo_ref_dcolsc(int kmax, double alpha, struct blasfeo_dmat *sA, int ai, int aj); -void blasfeo_ref_dcolsw(int kmax, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sC, int ci, int cj); -void blasfeo_ref_dcolpe(int kmax, int *ipiv, struct blasfeo_dmat *sA); -void blasfeo_ref_dcolpei(int kmax, int *ipiv, struct blasfeo_dmat *sA); - -// vec -// a <= alpha -void blasfeo_ref_dvecse(int m, double alpha, struct blasfeo_dvec *sx, int xi); -// sx[xi] <= a -void blasfeo_ref_dvecin1(double a, struct blasfeo_dvec *sx, int xi); -// <= sx[xi] -double blasfeo_ref_dvecex1(struct blasfeo_dvec *sx, int xi); -// y <= x -void blasfeo_ref_dveccp(int m, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi); -// x <= alpha*x -void blasfeo_ref_dvecsc(int m, double alpha, struct blasfeo_dvec *sx, int xi); -// y <= alpha*x -void blasfeo_ref_dveccpsc(int m, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi); -void blasfeo_ref_dvecad_sp(int m, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dvec *sz, int zi); -void blasfeo_ref_dvecin_sp(int m, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dvec *sz, int zi); -void blasfeo_ref_dvecex_sp(int m, double alpha, int *idx, struct blasfeo_dvec *sx, int x, struct blasfeo_dvec *sz, int zi); -// z += alpha * x[idx] -void blasfeo_ref_dvecexad_sp(int m, double alpha, int *idx, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); - -void blasfeo_ref_dveccl(int m, - struct blasfeo_dvec *sxm, int xim, struct blasfeo_dvec *sx, int xi, - struct blasfeo_dvec *sxp, int xip, struct blasfeo_dvec *sz, int zi); - -void blasfeo_ref_dveccl_mask(int m, - struct blasfeo_dvec *sxm, int xim, struct blasfeo_dvec *sx, int xi, - struct blasfeo_dvec *sxp, int xip, struct blasfeo_dvec *sz, int zi, - struct blasfeo_dvec *sm, int mi); - -void blasfeo_ref_dvecze(int m, struct blasfeo_dvec *sm, int mi, struct blasfeo_dvec *sv, int vi, struct blasfeo_dvec *se, int ei); -void blasfeo_ref_dvecnrm_inf(int m, struct blasfeo_dvec *sx, int xi, double *ptr_norm); -void blasfeo_ref_dvecpe(int kmax, int *ipiv, struct blasfeo_dvec *sx, int xi); -void blasfeo_ref_dvecpei(int kmax, int *ipiv, struct blasfeo_dvec *sx, int xi); - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_D_AUX_REF_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_d_aux_test.h b/third_party/acados/include/blasfeo/include/blasfeo_d_aux_test.h deleted file mode 100644 index 1c61635f3f..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_d_aux_test.h +++ /dev/null @@ -1,226 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -/* - * auxiliary algebra operations header - * - * include/blasfeo_aux_lib*.h - * - */ - -#ifndef BLASFEO_D_AUX_TEST_H_ -#define BLASFEO_D_AUX_TEST_H_ - -#include "blasfeo_common.h" - - -#ifdef __cplusplus -extern "C" { -#endif - -// --- memory calculations -int test_blasfeo_memsize_dmat(int m, int n); -int test_blasfeo_memsize_diag_dmat(int m, int n); -int test_blasfeo_memsize_dvec(int m); - -// --- creation -void test_blasfeo_create_dmat(int m, int n, struct blasfeo_dmat *sA, void *memory); -void test_blasfeo_create_dvec(int m, struct blasfeo_dvec *sA, void *memory); - -// --- conversion -void test_blasfeo_pack_dmat(int m, int n, double *A, int lda, struct blasfeo_dmat *sA, int ai, int aj); -void test_blasfeo_pack_dvec(int m, double *x, int xi, struct blasfeo_dvec *sa, int ai); -void test_blasfeo_pack_tran_dmat(int m, int n, double *A, int lda, struct blasfeo_dmat *sA, int ai, int aj); -void test_blasfeo_unpack_dmat(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, double *A, int lda); -void test_blasfeo_unpack_dvec(int m, struct blasfeo_dvec *sa, int ai, double *x, int xi); -void test_blasfeo_unpack_tran_dmat(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, double *A, int lda); - -// --- cast -void test_d_cast_mat2strmat(double *A, struct blasfeo_dmat *sA); -void test_d_cast_diag_mat2strmat(double *dA, struct blasfeo_dmat *sA); -void test_d_cast_vec2vecmat(double *a, struct blasfeo_dvec *sa); - -// ------ copy / scale - -// B <= A -void test_blasfeo_dgecp(int m, int n, - struct blasfeo_dmat *sA, int ai, int aj, - struct blasfeo_dmat *sB, int bi, int bj); - -// A <= alpha*A -void test_blasfeo_dgesc(int m, int n, - double alpha, - struct blasfeo_dmat *sA, int ai, int aj); - -// B <= alpha*A -void test_blasfeo_dgecpsc(int m, int n, - double alpha, - struct blasfeo_dmat *sA, int ai, int aj, - struct blasfeo_dmat *sB, int bi, int bj); - -// // --- insert/extract -// // -// // <= sA[ai, aj] -// void test_blasfeo_dgein1(double a, struct blasfeo_dmat *sA, int ai, int aj); -// // <= sA[ai, aj] -// double blasfeo_dgeex1(struct blasfeo_dmat *sA, int ai, int aj); -// // sx[xi] <= a -// void test_blasfeo_dvecin1(double a, struct blasfeo_dvec *sx, int xi); -// // <= sx[xi] -// double blasfeo_dvecex1(struct blasfeo_dvec *sx, int xi); -// // A <= alpha - -// // --- set -// void test_blasfeo_dgese(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj); -// // a <= alpha -// void test_blasfeo_dvecse(int m, double alpha, struct blasfeo_dvec *sx, int xi); -// // B <= A - - -// // --- vector -// // y <= x -// void test_blasfeo_dveccp(int m, struct blasfeo_dvec *sa, int ai, struct blasfeo_dvec *sc, int ci); -// // x <= alpha*x -// void test_blasfeo_dvecsc(int m, double alpha, struct blasfeo_dvec *sa, int ai); -// // TODO -// // x <= alpha*x -// void test_blasfeo_dveccpsc(int m, double alpha, struct blasfeo_dvec *sa, int ai, struct blasfeo_dvec *sc, int ci); - - -// // B <= A, A lower triangular -// void test_blasfeo_dtrcp_l(int m, -// struct blasfeo_dmat *sA, int ai, int aj, -// struct blasfeo_dmat *sB, int bi, int bj); - -// void test_blasfeo_dtrcpsc_l(int m, double alpha, -// struct blasfeo_dmat *sA, int ai, int aj, -// struct blasfeo_dmat *sB, int bi, int bj); - -// void test_blasfeo_dtrsc_l(int m, double alpha, -// struct blasfeo_dmat *sA, int ai, int aj); - - -// // B <= B + alpha*A -// void test_blasfeo_dgead(int m, int n, double alpha, -// struct blasfeo_dmat *sA, int ai, int aj, -// struct blasfeo_dmat *sC, int ci, int cj); - -// // y <= y + alpha*x -// void test_blasfeo_dvecad(int m, double alpha, -// struct blasfeo_dvec *sa, int ai, -// struct blasfeo_dvec *sc, int ci); - -// // --- traspositions -// void test_dgetr_lib(int m, int n, double alpha, int offsetA, double *pA, int sda, int offsetC, double *pC, int sdc); -// void test_blasfeo_dgetr(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sC, int ci, int cj); -// void test_dtrtr_l_lib(int m, double alpha, int offsetA, double *pA, int sda, int offsetC, double *pC, int sdc); -// void test_blasfeo_dtrtr_l(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sC, int ci, int cj); -// void test_dtrtr_u_lib(int m, double alpha, int offsetA, double *pA, int sda, int offsetC, double *pC, int sdc); -// void test_blasfeo_dtrtr_u(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sC, int ci, int cj); -// void test_blasfeo_ddiare(int kmax, double alpha, struct blasfeo_dmat *sA, int ai, int aj); -// void test_blasfeo_ddiain(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -// void test_ddiaex_lib(int kmax, double alpha, int offset, double *pD, int sdd, double *x); -// void test_ddiaad_lib(int kmax, double alpha, double *x, int offset, double *pD, int sdd); -// void test_ddiain_libsp(int kmax, int *idx, double alpha, double *x, double *pD, int sdd); -// void test_blasfeo_ddiain_sp(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dmat *sD, int di, int dj); -// void test_ddiaex_libsp(int kmax, int *idx, double alpha, double *pD, int sdd, double *x); -// void test_blasfeo_ddiaex(int kmax, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi); -// void test_blasfeo_ddiaex_sp(int kmax, double alpha, int *idx, struct blasfeo_dmat *sD, int di, int dj, struct blasfeo_dvec *sx, int xi); -// void test_blasfeo_ddiaad(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -// void test_ddiaad_libsp(int kmax, int *idx, double alpha, double *x, double *pD, int sdd); -// void test_blasfeo_ddiaad_sp(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dmat *sD, int di, int dj); -// void test_ddiaadin_libsp(int kmax, int *idx, double alpha, double *x, double *y, double *pD, int sdd); -// void test_blasfeo_ddiaadin_sp(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi, int *idx, struct blasfeo_dmat *sD, int di, int dj); -// void test_drowin_lib(int kmax, double alpha, double *x, double *pD); -// void test_blasfeo_drowin(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -// void test_drowex_lib(int kmax, double alpha, double *pD, double *x); -// void test_blasfeo_drowex(int kmax, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi); -// void test_drowad_lib(int kmax, double alpha, double *x, double *pD); -// void test_blasfeo_drowad(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -// void test_drowin_libsp(int kmax, double alpha, int *idx, double *x, double *pD); -// void test_drowad_libsp(int kmax, int *idx, double alpha, double *x, double *pD); -// void test_blasfeo_drowad_sp(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dmat *sD, int di, int dj); -// void test_drowadin_libsp(int kmax, int *idx, double alpha, double *x, double *y, double *pD); -// void test_drowsw_lib(int kmax, double *pA, double *pC); -// void test_blasfeo_drowsw(int kmax, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sC, int ci, int cj); -// void test_blasfeo_drowpe(int kmax, int *ipiv, struct blasfeo_dmat *sA); -// void test_blasfeo_dcolex(int kmax, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi); -// void test_dcolin_lib(int kmax, double *x, int offset, double *pD, int sdd); -// void test_blasfeo_dcolin(int kmax, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -// void test_dcolad_lib(int kmax, double alpha, double *x, int offset, double *pD, int sdd); -// void test_dcolin_libsp(int kmax, int *idx, double *x, double *pD, int sdd); -// void test_dcolad_libsp(int kmax, double alpha, int *idx, double *x, double *pD, int sdd); -// void test_dcolsw_lib(int kmax, int offsetA, double *pA, int sda, int offsetC, double *pC, int sdc); -// void test_blasfeo_dcolsw(int kmax, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sC, int ci, int cj); -// void test_blasfeo_dcolpe(int kmax, int *ipiv, struct blasfeo_dmat *sA); -// void test_dvecin_libsp(int kmax, int *idx, double *x, double *y); -// void test_dvecad_libsp(int kmax, int *idx, double alpha, double *x, double *y); -// void test_blasfeo_dvecad_sp(int m, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dvec *sz, int zi); -// void test_blasfeo_dvecin_sp(int m, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dvec *sz, int zi); -// void test_blasfeo_dvecex_sp(int m, double alpha, int *idx, struct blasfeo_dvec *sx, int x, struct blasfeo_dvec *sz, int zi); -// void test_blasfeo_dveccl(int m, struct blasfeo_dvec *sxm, int xim, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sxp, int xip, struct blasfeo_dvec *sz, int zi); -// void test_blasfeo_dveccl_mask(int m, struct blasfeo_dvec *sxm, int xim, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sxp, int xip, struct blasfeo_dvec *sz, int zi, struct blasfeo_dvec *sm, int mi); -// void test_blasfeo_dvecze(int m, struct blasfeo_dvec *sm, int mi, struct blasfeo_dvec *sv, int vi, struct blasfeo_dvec *se, int ei); -// void test_blasfeo_dvecnrm_inf(int m, struct blasfeo_dvec *sx, int xi, double *ptr_norm); -// void test_blasfeo_dvecpe(int kmax, int *ipiv, struct blasfeo_dvec *sx, int xi); -// void test_blasfeo_dvecpei(int kmax, int *ipiv, struct blasfeo_dvec *sx, int xi); - -// ext_dep - -void test_blasfeo_allocate_dmat(int m, int n, struct blasfeo_dmat *sA); -void test_blasfeo_allocate_dvec(int m, struct blasfeo_dvec *sa); - -void test_blasfeo_free_dmat(struct blasfeo_dmat *sA); -void test_blasfeo_free_dvec(struct blasfeo_dvec *sa); - -void test_blasfeo_print_dmat(int m, int n, struct blasfeo_dmat *sA, int ai, int aj); -void test_blasfeo_print_dvec(int m, struct blasfeo_dvec *sa, int ai); -void test_blasfeo_print_tran_dvec(int m, struct blasfeo_dvec *sa, int ai); - -void test_blasfeo_print_to_file_dmat(FILE *file, int m, int n, struct blasfeo_dmat *sA, int ai, int aj); -void test_blasfeo_print_to_file_dvec(FILE *file, int m, struct blasfeo_dvec *sa, int ai); -void test_blasfeo_print_to_file_tran_dvec(FILE *file, int m, struct blasfeo_dvec *sa, int ai); - -void test_blasfeo_print_exp_dmat(int m, int n, struct blasfeo_dmat *sA, int ai, int aj); -void test_blasfeo_print_exp_dvec(int m, struct blasfeo_dvec *sa, int ai); -void test_blasfeo_print_exp_tran_dvec(int m, struct blasfeo_dvec *sa, int ai); - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_D_AUX_TEST_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_d_blas.h b/third_party/acados/include/blasfeo/include/blasfeo_d_blas.h deleted file mode 100644 index ea8d006731..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_d_blas.h +++ /dev/null @@ -1,46 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_D_BLAS_H_ -#define BLASFEO_D_BLAS_H_ - - - -#include "blasfeo_d_blasfeo_api.h" -#include "blasfeo_d_blas_api.h" - - - -#endif // BLASFEO_D_BLAS_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_d_blas_api.h b/third_party/acados/include/blasfeo/include/blasfeo_d_blas_api.h deleted file mode 100644 index 2eab1e4094..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_d_blas_api.h +++ /dev/null @@ -1,281 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef BLASFEO_D_BLAS_API_H_ -#define BLASFEO_D_BLAS_API_H_ - - - -#include "blasfeo_target.h" - - - -#ifdef BLAS_API -#ifdef CBLAS_API -#ifndef BLASFEO_CBLAS_ENUM -#define BLASFEO_CBLAS_ENUM -#ifdef FORTRAN_BLAS_API -#ifndef CBLAS_H -enum CBLAS_LAYOUT {CblasRowMajor=101, CblasColMajor=102}; -enum CBLAS_TRANSPOSE {CblasNoTrans=111, CblasTrans=112, CblasConjTrans=113}; -enum CBLAS_UPLO {CblasUpper=121, CblasLower=122}; -enum CBLAS_DIAG {CblasNonUnit=131, CblasUnit=132}; -enum CBLAS_SIDE {CblasLeft=141, CblasRight=142}; -#define CBLAS_ORDER CBLAS_LAYOUT /* this for backward compatibility with CBLAS_ORDER */ -#endif // CBLAS_H -#else // FORTRAN_BLAS_API -enum BLASFEO_CBLAS_LAYOUT {BlasfeoCblasRowMajor=101, BlasfeoCblasColMajor=102}; -enum BLASFEO_CBLAS_TRANSPOSE {BlasfeoCblasNoTrans=111, BlasfeoCblasTrans=112, BlasfeoCblasConjTrans=113}; -enum BLASFEO_CBLAS_UPLO {BlasfeoCblasUpper=121, BlasfeoCblasLower=122}; -enum BLASFEO_CBLAS_DIAG {BlasfeoCblasNonUnit=131, BlasfeoCblasUnit=132}; -enum BLASFEO_CBLAS_SIDE {BlasfeoCblasLeft=141, BlasfeoCblasRight=142}; -#define BLASFEO_CBLAS_ORDER BLASFEO_CBLAS_LAYOUT /* this for backward compatibility with BLASFEO_CBLAS_ORDER */ -#endif // FORTRAN_BLAS_API -#endif // BLASFEO_CBLAS_ENUM -#endif // CBLAS_API -#endif // BLAS_API - - -#ifdef __cplusplus -extern "C" { -#endif - - - -#ifdef BLAS_API - - - -#ifdef FORTRAN_BLAS_API - - - -// BLAS 1 -// -void daxpy_(int *n, double *alpha, double *x, int *incx, double *y, int *incy); -// -void dcopy_(int *n, double *x, int *incx, double *y, int *incy); -// -double ddot_(int *n, double *x, int *incx, double *y, int *incy); - -// BLAS 2 -// -void dgemv_(char *tran, int *m, int *n, double *alpha, double *A, int *lda, double *x, int *incx, double *beta, double *y, int *incy); -// -void dsymv_(char *uplo, int *n, double *alpha, double *A, int *lda, double *x, int *incx, double *beta, double *y, int *incy); -// -void dger_(int *m, int *n, double *alpha, double *x, int *incx, double *y, int *incy, double *A, int *lda); - -// BLAS 3 -// -void dgemm_(char *ta, char *tb, int *m, int *n, int *k, double *alpha, double *A, int *lda, double *B, int *ldb, double *beta, double *C, int *ldc); -// -void dsyrk_(char *uplo, char *ta, int *m, int *k, double *alpha, double *A, int *lda, double *beta, double *C, int *ldc); -// -void dtrmm_(char *side, char *uplo, char *transa, char *diag, int *m, int *n, double *alpha, double *A, int *lda, double *B, int *ldb); -// -void dtrsm_(char *side, char *uplo, char *transa, char *diag, int *m, int *n, double *alpha, double *A, int *lda, double *B, int *ldb); -// -void dsyr2k_(char *uplo, char *ta, int *m, int *k, double *alpha, double *A, int *lda, double *B, int *ldb, double *beta, double *C, int *ldc); - - - -// LAPACK -// -void dgesv_(int *m, int *n, double *A, int *lda, int *ipiv, double *B, int *ldb, int *info); -// -void dgetrf_(int *m, int *n, double *A, int *lda, int *ipiv, int *info); -// -void dgetrf_np_(int *m, int *n, double *A, int *lda, int *info); -// -void dgetrs_(char *trans, int *m, int *n, double *A, int *lda, int *ipiv, double *B, int *ldb, int *info); -// -void dlaswp_(int *n, double *A, int *lda, int *k1, int *k2, int *ipiv, int *incx); -// -void dposv_(char *uplo, int *m, int *n, double *A, int *lda, double *B, int *ldb, int *info); -// -void dpotrf_(char *uplo, int *m, double *A, int *lda, int *info); -// -void dpotrs_(char *uplo, int *m, int *n, double *A, int *lda, double *B, int *ldb, int *info); -// -void dtrtrs_(char *uplo, char *trans, char *diag, int *m, int *n, double *A, int *lda, double *B, int *ldb, int *info); - - - -// aux -void dgetr_(int *m, int *n, double *A, int *lda, double *B, int *ldb); - - - -#ifdef CBLAS_API - - - -// CBLAS 1 -// -void cblas_daxpy(const int N, const double alpha, const double *X, const int incX, double *Y, const int incY); -// -void cblas_dswap(const int N, double *X, const int incX, double *Y, const int incY); -// -void cblas_dcopy(const int N, const double *X, const int incX, double *Y, const int incY); - -// CBLAS 2 -// -void cblas_dgemv(const enum CBLAS_LAYOUT layout, const enum CBLAS_TRANSPOSE TransA, const int M, const int N, const int K, const double alpha, const double *A, const int lda, const double *X, const int incX, const double beta, double *Y, const int incY); - -// CBLAS 3 -// -void cblas_dgemm(const enum CBLAS_LAYOUT layout, const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_TRANSPOSE TransB, const int M, const int N, const int K, const double alpha, const double *A, const int lda, const double *B, const int ldb, const double beta, double *C, const int ldc); -// -void cblas_dsyrk(const enum CBLAS_LAYOUT layout, const enum CBLAS_UPLO Uplo, const enum CBLAS_TRANSPOSE Trans, const int N, const int K, const double alpha, const double *A, const int lda, const double beta, double *C, const int ldc); -// -void cblas_dtrmm(const enum CBLAS_LAYOUT layout, const enum CBLAS_SIDE Side, const enum CBLAS_UPLO Uplo, const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, const int M, const int N, const double alpha, const double *A, const int lda, double *B, const int ldb); -// -void cblas_dtrsm(const enum CBLAS_LAYOUT layout, const enum CBLAS_SIDE Side, const enum CBLAS_UPLO Uplo, const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, const int M, const int N, const double alpha, const double *A, const int lda, double *B, const int ldb); - - - -#endif // CBLAS_API - - - -#else // BLASFEO_API - - - -// BLAS 1 -// -void blasfeo_blas_daxpy(int *n, double *alpha, double *x, int *incx, double *y, int *incy); -// -double blasfeo_blas_ddot(int *n, double *x, int *incx, double *y, int *incy); -// -void blasfeo_blas_dcopy(int *n, double *x, int *incx, double *y, int *incy); - -// BLAS 2 -// -void blasfeo_blas_dgemv(char *trans, int *m, int *n, double *alpha, double *A, int *lda, double *x, int *incx, double *beta, double *y, int *incy); -// -void blasfeo_blas_dsymv(char *uplo, int *n, double *alpha, double *A, int *lda, double *x, int *incx, double *beta, double *y, int *incy); -// -void blasfeo_blas_dger(int *m, int *n, double *alpha, double *x, int *incx, double *y, int *incy, double *A, int *lda); - -// BLAS 3 -// -void blasfeo_blas_dgemm(char *ta, char *tb, int *m, int *n, int *k, double *alpha, double *A, int *lda, double *B, int *ldb, double *beta, double *C, int *ldc); -// -void blasfeo_blas_dsyrk(char *uplo, char *ta, int *m, int *k, double *alpha, double *A, int *lda, double *beta, double *C, int *ldc); -// -void blasfeo_blas_dtrmm(char *side, char *uplo, char *transa, char *diag, int *m, int *n, double *alpha, double *A, int *lda, double *B, int *ldb); -// -void blasfeo_blas_dtrsm(char *side, char *uplo, char *transa, char *diag, int *m, int *n, double *alpha, double *A, int *lda, double *B, int *ldb); -// -void blasfeo_blas_dsyr2k(char *uplo, char *ta, int *m, int *k, double *alpha, double *A, int *lda, double *B, int *ldb, double *beta, double *C, int *ldc); - - - -// LAPACK -// -void blasfeo_lapack_dgesv(int *m, int *n, double *A, int *lda, int *ipiv, double *B, int *ldb, int *info); -// -void blasfeo_lapack_dgetrf(int *m, int *n, double *A, int *lda, int *ipiv, int *info); -// -void blasfeo_lapack_dgetrf_np(int *m, int *n, double *A, int *lda, int *info); -// -void blasfeo_lapack_dgetrs(char *trans, int *m, int *n, double *A, int *lda, int *ipiv, double *B, int *ldb, int *info); -// -void blasfeo_lapack_dlaswp(int *n, double *A, int *lda, int *k1, int *k2, int *ipiv, int *incx); -// -void blasfeo_lapack_dposv(char *uplo, int *m, int *n, double *A, int *lda, double *B, int *ldb, int *info); -// -void blasfeo_lapack_dpotrf(char *uplo, int *m, double *A, int *lda, int *info); -// -void blasfeo_lapack_dpotrs(char *uplo, int *m, int *n, double *A, int *lda, double *B, int *ldb, int *info); -// -void blasfeo_lapack_dtrtrs(char *uplo, char *trans, char *diag, int *m, int *n, double *A, int *lda, double *B, int *ldb, int *info); - - - -// aux -void blasfeo_blas_dgetr(int *m, int *n, double *A, int *lda, double *B, int *ldb); - - - -#ifdef CBLAS_API - - - -// CBLAS 1 -// -void blasfeo_cblas_daxpy(const int N, const double alpha, const double *X, const int incX, double *Y, const int incY); -// -void blasfeo_cblas_dswap(const int N, double *X, const int incX, double *Y, const int incY); -// -void blasfeo_cblas_dcopy(const int N, const double *X, const int incX, double *Y, const int incY); - -// CBLAS 2 -// -void blasfeo_cblas_dgemv(const enum BLASFEO_CBLAS_LAYOUT layout, const enum BLASFEO_CBLAS_TRANSPOSE TransA, const int M, const int N, const double alpha, const double *A, const int lda, const double *X, const int incX, const double beta, double *Y, const int incY); - -// CBLAS 3 -// -void blasfeo_cblas_dgemm(const enum BLASFEO_CBLAS_LAYOUT layout, const enum BLASFEO_CBLAS_TRANSPOSE TransA, const enum BLASFEO_CBLAS_TRANSPOSE TransB, const int M, const int N, const int K, const double alpha, const double *A, const int lda, const double *B, const int ldb, const double beta, double *C, const int ldc); -// -void blasfeo_cblas_dsyrk(const enum BLASFEO_CBLAS_LAYOUT layout, const enum BLASFEO_CBLAS_UPLO Uplo, const enum BLASFEO_CBLAS_TRANSPOSE Trans, const int N, const int K, const double alpha, const double *A, const int lda, const double beta, double *C, const int ldc); -// -void blasfeo_cblas_dtrmm(const enum BLASFEO_CBLAS_LAYOUT layout, const enum BLASFEO_CBLAS_SIDE Side, const enum BLASFEO_CBLAS_UPLO Uplo, const enum BLASFEO_CBLAS_TRANSPOSE TransA, const enum BLASFEO_CBLAS_DIAG Diag, const int M, const int N, const double alpha, const double *A, const int lda, double *B, const int ldb); -// -void blasfeo_cblas_dtrsm(const enum BLASFEO_CBLAS_LAYOUT layout, const enum BLASFEO_CBLAS_SIDE Side, const enum BLASFEO_CBLAS_UPLO Uplo, const enum BLASFEO_CBLAS_TRANSPOSE TransA, const enum BLASFEO_CBLAS_DIAG Diag, const int M, const int N, const double alpha, const double *A, const int lda, double *B, const int ldb); - - - -#endif // CBLAS_API - - - -#endif // BLASFEO_API - - - -#endif // BLAS_API - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_D_BLAS_API_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_d_blasfeo_api.h b/third_party/acados/include/blasfeo/include/blasfeo_d_blasfeo_api.h deleted file mode 100644 index 88bb3fce22..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_d_blasfeo_api.h +++ /dev/null @@ -1,364 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_D_BLASFEO_API_H_ -#define BLASFEO_D_BLASFEO_API_H_ - - - -#include "blasfeo_common.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -// level 1 BLAS -// - -// z = y + alpha*x -// z[zi:zi+n] = alpha*x[xi:xi+n] + y[yi:yi+n] -// NB: Different arguments semantic compare to equivalent standard BLAS routine -void blasfeo_daxpy(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// z = beta*y + alpha*x -void blasfeo_daxpby(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// z = x .* y -void blasfeo_dvecmul(int m, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// z += x .* y -void blasfeo_dvecmulacc(int m, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// z = x .* y, return sum(z) = x^T * y -double blasfeo_dvecmuldot(int m, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// return x^T * y -double blasfeo_ddot(int m, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi); -// construct givens plane rotation -void blasfeo_drotg(double a, double b, double *c, double *s); -// apply plane rotation [a b] [c -s; s; c] to the aj0 and aj1 columns of A at row index ai -void blasfeo_dcolrot(int m, struct blasfeo_dmat *sA, int ai, int aj0, int aj1, double c, double s); -// apply plane rotation [c s; -s c] [a; b] to the ai0 and ai1 rows of A at column index aj -void blasfeo_drowrot(int m, struct blasfeo_dmat *sA, int ai0, int ai1, int aj, double c, double s); - - - -// -// level 2 BLAS -// - -// dense - -// z <= beta * y + alpha * A * x -void blasfeo_dgemv_n(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// z <= beta * y + alpha * A^T * x -void blasfeo_dgemv_t(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A ) * x, A (m)x(n) -void blasfeo_dtrsv_lnn_mn(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A^T ) * x, A (m)x(n) -void blasfeo_dtrsv_ltn_mn(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A ) * x, A (m)x(m) lower, not_transposed, not_unit -void blasfeo_dtrsv_lnn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A ) * x, A (m)x(m) lower, not_transposed, unit -void blasfeo_dtrsv_lnu(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A^T ) * x, A (m)x(m) lower, transposed, not_unit -void blasfeo_dtrsv_ltn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A^T ) * x, A (m)x(m) lower, transposed, unit -void blasfeo_dtrsv_ltu(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A^T ) * x, A (m)x(m) upper, not_transposed, not_unit -void blasfeo_dtrsv_unn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A^T ) * x, A (m)x(m) upper, transposed, not_unit -void blasfeo_dtrsv_utn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= A * x ; A lower triangular -void blasfeo_dtrmv_lnn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= A * x ; A lower triangular, unit diagonal -void blasfeo_dtrmv_lnu(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= A^T * x ; A lower triangular -void blasfeo_dtrmv_ltn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= A^T * x ; A lower triangular, unit diagonal -void blasfeo_dtrmv_ltu(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= beta * y + alpha * A * x ; A upper triangular -void blasfeo_dtrmv_unn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= A^T * x ; A upper triangular -void blasfeo_dtrmv_utn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z_n <= beta_n * y_n + alpha_n * A * x_n -// z_t <= beta_t * y_t + alpha_t * A^T * x_t -void blasfeo_dgemv_nt(int m, int n, double alpha_n, double alpha_t, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx_n, int xi_n, struct blasfeo_dvec *sx_t, int xi_t, double beta_n, double beta_t, struct blasfeo_dvec *sy_n, int yi_n, struct blasfeo_dvec *sy_t, int yi_t, struct blasfeo_dvec *sz_n, int zi_n, struct blasfeo_dvec *sz_t, int zi_t); -// z <= beta * y + alpha * A * x, where A is symmetric and only the lower triangular patr of A is accessed -void blasfeo_dsymv_l(int m, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -void blasfeo_dsymv_l_mn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// z <= beta * y + alpha * A * x, where A is symmetric and only the upper triangular patr of A is accessed -void blasfeo_dsymv_u(int m, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// D = C + alpha * x * y^T -void blasfeo_dger(int m, int n, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); - -// diagonal - -// z <= beta * y + alpha * A * x, A diagonal -void blasfeo_dgemv_d(int m, double alpha, struct blasfeo_dvec *sA, int ai, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); - - - -// -// level 3 BLAS -// - -// dense - -// D <= beta * C + alpha * A * B -void blasfeo_dgemm_nn(int m, int n, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T -void blasfeo_dgemm_nt(int m, int n, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B -void blasfeo_dgemm_tn(int m, int n, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B^T -void blasfeo_dgemm_tt(int m, int n, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T ; C, D lower triangular -void blasfeo_dsyrk_ln(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -void blasfeo_dsyrk_ln_mn(int m, int n, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -#if ( defined(LA_HIGH_PERFORMANCE) & defined(MF_COLMAJ) ) -void blasfeo_dsyrk3_ln(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -#endif -// D <= beta * C + alpha * A^T * B ; C, D lower triangular -void blasfeo_dsyrk_lt(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -#if ( defined(LA_HIGH_PERFORMANCE) & defined(MF_COLMAJ) ) -void blasfeo_dsyrk3_lt(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -#endif -// D <= beta * C + alpha * A * B^T ; C, D upper triangular -void blasfeo_dsyrk_un(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -#if ( defined(LA_HIGH_PERFORMANCE) & defined(MF_COLMAJ) ) -void blasfeo_dsyrk3_un(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -#endif -// D <= beta * C + alpha * A^T * B ; C, D upper triangular -void blasfeo_dsyrk_ut(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -#if ( defined(LA_HIGH_PERFORMANCE) & defined(MF_COLMAJ) ) -void blasfeo_dsyrk3_ut(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -#endif -// D <= alpha * A * B ; A lower triangular -void blasfeo_dtrmm_llnn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A * B ; A lower triangular -void blasfeo_dtrmm_llnu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^T * B ; A lower triangular -void blasfeo_dtrmm_lltn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^T * B ; A lower triangular -void blasfeo_dtrmm_lltu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A * B ; A upper triangular -void blasfeo_dtrmm_lunn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A * B ; A upper triangular -void blasfeo_dtrmm_lunu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^T * B ; A upper triangular -void blasfeo_dtrmm_lutn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^T * B ; A upper triangular -void blasfeo_dtrmm_lutu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A ; A lower triangular -void blasfeo_dtrmm_rlnn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A ; A lower triangular -void blasfeo_dtrmm_rlnu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^T ; A lower triangular -void blasfeo_dtrmm_rltn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^T ; A lower triangular -void blasfeo_dtrmm_rltu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A ; A upper triangular -void blasfeo_dtrmm_runn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A ; A upper triangular -void blasfeo_dtrmm_runu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^T ; A upper triangular -void blasfeo_dtrmm_rutn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^T ; A upper triangular -void blasfeo_dtrmm_rutu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A lower triangular employint explicit inverse of diagonal -// D <= alpha * A^{-1} * B , with A lower triangular employing explicit inverse of diagonal -void blasfeo_dtrsm_llnn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A lower triangular with unit diagonal -void blasfeo_dtrsm_llnu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A lower triangular employing explicit inverse of diagonal -void blasfeo_dtrsm_lltn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A lower triangular with unit diagonal -void blasfeo_dtrsm_lltu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A upper triangular employing explicit inverse of diagonal -void blasfeo_dtrsm_lunn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A upper triangular with unit diagonal -void blasfeo_dtrsm_lunu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A upper triangular employing explicit inverse of diagonal -void blasfeo_dtrsm_lutn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A upper triangular with unit diagonal -void blasfeo_dtrsm_lutu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A lower triangular employing explicit inverse of diagonal -void blasfeo_dtrsm_rlnn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A lower triangular with unit diagonal -void blasfeo_dtrsm_rlnu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A lower triangular employing explicit inverse of diagonal -void blasfeo_dtrsm_rltn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A lower triangular with unit diagonal -void blasfeo_dtrsm_rltu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A upper triangular employing explicit inverse of diagonal -void blasfeo_dtrsm_runn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A upper triangular with unit diagonal -void blasfeo_dtrsm_runu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A upper triangular employing explicit inverse of diagonal -void blasfeo_dtrsm_rutn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A upper triangular with unit diagonal -void blasfeo_dtrsm_rutu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T + alpha * B * A^T; C, D lower triangular -void blasfeo_dsyr2k_ln(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B + alpha * B^T * A; C, D lower triangular -void blasfeo_dsyr2k_lt(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T + alpha * B * A^T; C, D upper triangular -void blasfeo_dsyr2k_un(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B + alpha * B^T * A; C, D upper triangular -void blasfeo_dsyr2k_ut(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); - -// diagonal - -// D <= alpha * A * B + beta * C, with A diagonal (stored as strvec) -void dgemm_diag_left_lib(int m, int n, double alpha, double *dA, double *pB, int sdb, double beta, double *pC, int sdc, double *pD, int sdd); -void blasfeo_dgemm_dn(int m, int n, double alpha, struct blasfeo_dvec *sA, int ai, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A * B + beta * C, with B diagonal (stored as strvec) -void blasfeo_dgemm_nd(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sB, int bi, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); - - - -// -// LAPACK -// - -// D <= chol( C ) ; C, D lower triangular -void blasfeo_dpotrf_l(int m, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -void blasfeo_dpotrf_l_mn(int m, int n, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= chol( C ) ; C, D upper triangular -void blasfeo_dpotrf_u(int m, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= chol( C + A * B' ) ; C, D lower triangular -// D <= chol( C + A * B^T ) ; C, D lower triangular -void blasfeo_dsyrk_dpotrf_ln(int m, int k, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -void blasfeo_dsyrk_dpotrf_ln_mn(int m, int n, int k, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= lu( C ) ; no pivoting -void blasfeo_dgetrf_np(int m, int n, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= lu( C ) ; row pivoting -void blasfeo_dgetrf_rp(int m, int n, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj, int *ipiv); -// D <= qr( C ) -int blasfeo_dgeqrf_worksize(int m, int n); // in bytes -void blasfeo_dgeqrf(int m, int n, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj, void *work); -// D <= Q factor, where C is the output of the LQ factorization -int blasfeo_dorglq_worksize(int m, int n, int k); // in bytes -void blasfeo_dorglq(int m, int n, int k, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj, void *work); -// D <= lq( C ) -void blasfeo_dgelqf(int m, int n, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj, void *work); -int blasfeo_dgelqf_worksize(int m, int n); // in bytes -// D <= lq( C ), positive diagonal elements -void blasfeo_dgelqf_pd(int m, int n, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj, void *work); -// [L, A] <= lq( [L, A] ), positive diagonal elements, array of matrices, with -// L lower triangular, of size (m)x(m) -// A full, of size (m)x(n1) -void blasfeo_dgelqf_pd_la(int m, int n1, struct blasfeo_dmat *sL, int li, int lj, struct blasfeo_dmat *sA, int ai, int aj, void *work); -// [L, L, A] <= lq( [L, L, A] ), positive diagonal elements, array of matrices, with: -// L lower triangular, of size (m)x(m) -// A full, of size (m)x(n1) -void blasfeo_dgelqf_pd_lla(int m, int n1, struct blasfeo_dmat *sL0, int l0i, int l0j, struct blasfeo_dmat *sL1, int l1i, int l1j, struct blasfeo_dmat *sA, int ai, int aj, void *work); - - - -// -// BLAS API helper functions -// - -#if ( defined(BLAS_API) & defined(MF_PANELMAJ) ) -// BLAS 3 -void blasfeo_cm_dgemm_nn(int m, int n, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dgemm_nt(int m, int n, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dgemm_tn(int m, int n, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dgemm_tt(int m, int n, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dsyrk_ln(int m, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dsyrk_lt(int m, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dsyrk_un(int m, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dsyrk_ut(int m, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dsyrk3_ln(int m, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dsyrk3_lt(int m, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dsyrk3_un(int m, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dsyrk3_ut(int m, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_llnn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_llnu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_lltn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_lltu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_lunn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_lunu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_lutn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_lutu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_rlnn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_rlnu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_rltn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_rltu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_runn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_runu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_rutn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_rutu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_llnn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_llnu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_lltn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_lltu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_lunn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_lunu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_lutn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_lutu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_rlnn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_rlnu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_rltn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_rltu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_runn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_runu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_rutn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_rutu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dsyr2k_ln(int m, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dsyr2k_lt(int m, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dsyr2k_un(int m, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dsyr2k_ut(int m, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -// BLAS 2 -void blasfeo_cm_dgemv_n(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dvec *sx, int xi, double beta, struct blasfeo_cm_dvec *sy, int yi, struct blasfeo_cm_dvec *sz, int zi); -void blasfeo_cm_dgemv_t(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dvec *sx, int xi, double beta, struct blasfeo_cm_dvec *sy, int yi, struct blasfeo_cm_dvec *sz, int zi); -void blasfeo_cm_dsymv_l(int m, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dvec *sx, int xi, double beta, struct blasfeo_cm_dvec *sy, int yi, struct blasfeo_cm_dvec *sz, int zi); -void blasfeo_cm_dsymv_u(int m, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dvec *sx, int xi, double beta, struct blasfeo_cm_dvec *sy, int yi, struct blasfeo_cm_dvec *sz, int zi); -void blasfeo_cm_dger(int m, int n, double alpha, struct blasfeo_cm_dvec *sx, int xi, struct blasfeo_cm_dvec *sy, int yi, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -// LAPACK -void blasfeo_cm_dpotrf_l(int m, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dpotrf_u(int m, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dgetrf_rp(int m, int n, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj, int *ipiv); -#endif - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_D_BLASFEO_API_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_d_blasfeo_api_ref.h b/third_party/acados/include/blasfeo/include/blasfeo_d_blasfeo_api_ref.h deleted file mode 100644 index 141a1f0f06..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_d_blasfeo_api_ref.h +++ /dev/null @@ -1,147 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_D_BLASFEO_API_REF_H_ -#define BLASFEO_D_BLASFEO_API_REF_H_ - -#include "blasfeo_common.h" - - -#ifdef __cplusplus -extern "C" { -#endif - - -// expose reference BLASFEO for testing - -// --- level 1 - -void blasfeo_daxpy_ref(int kmax, double alpha, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sy, int yi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_daxpby_ref(int kmax, double alpha, struct blasfeo_dvec_ref *sx, int xi, double beta, struct blasfeo_dvec_ref *sy, int yi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dvecmul_ref(int m, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sy, int yi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dvecmulacc_ref(int m, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sy, int yi, struct blasfeo_dvec_ref *sz, int zi); -double blasfeo_dvecmuldot_ref(int m, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sy, int yi, struct blasfeo_dvec_ref *sz, int zi); -double blasfeo_ddot_ref(int m, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sy, int yi); -void blasfeo_drotg_ref(double a, double b, double *c, double *s); -void blasfeo_dcolrot_ref(int m, struct blasfeo_dmat_ref *sA, int ai, int aj0, int aj1, double c, double s); -void blasfeo_drowrot_ref(int m, struct blasfeo_dmat_ref *sA, int ai0, int ai1, int aj, double c, double s); - - -// --- level 2 - -// dense -void blasfeo_dgemv_n_ref(int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, double beta, struct blasfeo_dvec_ref *sy, int yi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dgemv_t_ref(int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, double beta, struct blasfeo_dvec_ref *sy, int yi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dtrsv_lnn_mn_ref(int m, int n, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dtrsv_ltn_mn_ref(int m, int n, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dtrsv_lnn_ref(int m, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dtrsv_lnu_ref(int m, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dtrsv_ltn_ref(int m, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dtrsv_ltu_ref(int m, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dtrsv_unn_ref(int m, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dtrsv_utn_ref(int m, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dtrmv_unn_ref(int m, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dtrmv_utn_ref(int m, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dtrmv_lnn_ref(int m, int n, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dtrmv_ltn_ref(int m, int n, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dtrmv_lnu_ref(int m, int n, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dtrmv_ltu_ref(int m, int n, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dgemv_nt_ref(int m, int n, double alpha_n, double alpha_t, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx_n, int xi_n, struct blasfeo_dvec_ref *sx_t, int xi_t, double beta_n, double beta_t, struct blasfeo_dvec_ref *sy_n, int yi_n, struct blasfeo_dvec_ref *sy_t, int yi_t, struct blasfeo_dvec_ref *sz_n, int zi_n, struct blasfeo_dvec_ref *sz_t, int zi_t); -void blasfeo_dsymv_l_ref(int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, double beta, struct blasfeo_dvec_ref *sy, int yi, struct blasfeo_dvec_ref *sz, int zi); - -// diagonal -void blasfeo_dgemv_d_ref(int m, double alpha, struct blasfeo_dvec_ref *sA, int ai, struct blasfeo_dvec_ref *sx, int xi, double beta, struct blasfeo_dvec_ref *sy, int yi, struct blasfeo_dvec_ref *sz, int zi); - - -// --- level 3 - -// dense -void blasfeo_dgemm_nn_ref( int m, int n, int k, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, double beta, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dgemm_nt_ref( int m, int n, int k, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, double beta, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dgemm_tn_ref(int m, int n, int k, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, double beta, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dgemm_tt_ref(int m, int n, int k, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, double beta, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); - -void blasfeo_dsyrk_ln_mn_ref( int m, int n, int k, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, double beta, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dsyrk_ln_ref( int m, int k, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, double beta, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dsyrk_lt_ref( int m, int k, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, double beta, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dsyrk_un_ref( int m, int k, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, double beta, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dsyrk_ut_ref( int m, int k, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, double beta, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); - -void blasfeo_dtrmm_rutn_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrmm_rlnn_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); - -void blasfeo_dtrsm_lunu_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_lunn_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_lutu_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_lutn_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_llnu_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_llnn_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_lltu_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_lltn_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_runu_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_runn_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_rutu_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_rutn_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_rlnu_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_rlnn_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_rltu_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_rltn_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); - -// diagonal -void dgemm_diag_left_lib_ref(int m, int n, double alpha, double *dA, double *pB, int sdb, double beta, double *pC, int sdc, double *pD, int sdd); -void blasfeo_dgemm_dn_ref(int m, int n, double alpha, struct blasfeo_dvec_ref *sA, int ai, struct blasfeo_dmat_ref *sB, int bi, int bj, double beta, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dgemm_nd_ref(int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sB, int bi, double beta, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); - -// --- lapack - -void blasfeo_dgetrf_nopivot_ref(int m, int n, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dgetrf_rowpivot_ref(int m, int n, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj, int *ipiv); -void blasfeo_dpotrf_l_ref(int m, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dpotrf_l_mn_ref(int m, int n, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dsyrk_dpotrf_ln_ref(int m, int k, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dsyrk_dpotrf_ln_mn_ref(int m, int n, int k, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dgetrf_nopivot_ref(int m, int n, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dgetrf_rowpivot_ref(int m, int n, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj, int *ipiv); -void blasfeo_dgeqrf_ref(int m, int n, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj, void *work); -void blasfeo_dgelqf_ref(int m, int n, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj, void *work); -void blasfeo_dgelqf_pd_ref(int m, int n, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj, void *work); -void blasfeo_dgelqf_pd_la_ref(int m, int n1, struct blasfeo_dmat_ref *sL, int li, int lj, struct blasfeo_dmat_ref *sA, int ai, int aj, void *work); -void blasfeo_dgelqf_pd_lla_ref(int m, int n1, struct blasfeo_dmat_ref *sL0, int l0i, int l0j, struct blasfeo_dmat_ref *sL1, int l1i, int l1j, struct blasfeo_dmat_ref *sA, int ai, int aj, void *work); - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_D_BLASFEO_API_REF_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_d_blasfeo_hp_api.h b/third_party/acados/include/blasfeo/include/blasfeo_d_blasfeo_hp_api.h deleted file mode 100644 index 405733f13e..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_d_blasfeo_hp_api.h +++ /dev/null @@ -1,84 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_D_BLASFEO_HP_API_H_ -#define BLASFEO_D_BLASFEO_HP_API_H_ - - - -#include "blasfeo_common.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -// level 3 BLAS -// - -// dense - - -// D <= beta * C + alpha * A^T * B -void blasfeo_hp_dgemm_tn(int m, int n, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T; C, D lower triangular -void blasfeo_hp_dsyrk_ln(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A * A^T ; C, D lower triangular -void blasfeo_hp_dsyrk3_ln(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A lower triangular -void blasfeo_hp_dtrsm_rltn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); - - -// -// level 2 BLAS -// - -// dense - -// z <= beta * y + alpha * A * x -void blasfeo_hp_dgemv_n(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_D_BLASFEO_HP_API_H_ - diff --git a/third_party/acados/include/blasfeo/include/blasfeo_d_blasfeo_ref_api.h b/third_party/acados/include/blasfeo/include/blasfeo_d_blasfeo_ref_api.h deleted file mode 100644 index 1a8b22c67e..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_d_blasfeo_ref_api.h +++ /dev/null @@ -1,283 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_D_BLASFEO_REF_API_H_ -#define BLASFEO_D_BLASFEO_REF_API_H_ - - - -#include "blasfeo_common.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -// level 1 BLAS -// - -// z = y + alpha*x -// z[zi:zi+n] = alpha*x[xi:xi+n] + y[yi:yi+n] -// NB: Different arguments semantic compare to equivalent standard BLAS routine -void blasfeo_ref_daxpy(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// z = beta*y + alpha*x -void blasfeo_ref_daxpby(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// z = x .* y -void blasfeo_ref_dvecmul(int m, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// z += x .* y -void blasfeo_ref_dvecmulacc(int m, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// z = x .* y, return sum(z) = x^T * y -double blasfeo_ref_dvecmuldot(int m, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// return x^T * y -double blasfeo_ref_ddot(int m, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi); -// construct givens plane rotation -void blasfeo_ref_drotg(double a, double b, double *c, double *s); -// apply plane rotation [a b] [c -s; s; c] to the aj0 and aj1 columns of A at row index ai -void blasfeo_ref_dcolrot(int m, struct blasfeo_dmat *sA, int ai, int aj0, int aj1, double c, double s); -// apply plane rotation [c s; -s c] [a; b] to the ai0 and ai1 rows of A at column index aj -void blasfeo_ref_drowrot(int m, struct blasfeo_dmat *sA, int ai0, int ai1, int aj, double c, double s); - - - -// -// level 2 BLAS -// - -// dense - -// z <= beta * y + alpha * A * x -void blasfeo_ref_dgemv_n(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// z <= beta * y + alpha * A' * x -void blasfeo_ref_dgemv_t(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A ) * x, A (m)x(n) -void blasfeo_ref_dtrsv_lnn_mn(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(n) -void blasfeo_ref_dtrsv_ltn_mn(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A ) * x, A (m)x(m) lower, not_transposed, not_unit -void blasfeo_ref_dtrsv_lnn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A ) * x, A (m)x(m) lower, not_transposed, unit -void blasfeo_ref_dtrsv_lnu(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(m) lower, transposed, not_unit -void blasfeo_ref_dtrsv_ltn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(m) lower, transposed, unit -void blasfeo_ref_dtrsv_ltu(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(m) upper, not_transposed, not_unit -void blasfeo_ref_dtrsv_unn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(m) upper, transposed, not_unit -void blasfeo_ref_dtrsv_utn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= A * x ; A lower triangular -void blasfeo_ref_dtrmv_lnn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= A * x ; A lower triangular, unit diagonal -void blasfeo_ref_dtrmv_lnu(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= A' * x ; A lower triangular -void blasfeo_ref_dtrmv_ltn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= A' * x ; A lower triangular, unit diagonal -void blasfeo_ref_dtrmv_ltu(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= beta * y + alpha * A * x ; A upper triangular -void blasfeo_ref_dtrmv_unn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= A' * x ; A upper triangular -void blasfeo_ref_dtrmv_utn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z_n <= beta_n * y_n + alpha_n * A * x_n -// z_t <= beta_t * y_t + alpha_t * A' * x_t -void blasfeo_ref_dgemv_nt(int m, int n, double alpha_n, double alpha_t, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx_n, int xi_n, struct blasfeo_dvec *sx_t, int xi_t, double beta_n, double beta_t, struct blasfeo_dvec *sy_n, int yi_n, struct blasfeo_dvec *sy_t, int yi_t, struct blasfeo_dvec *sz_n, int zi_n, struct blasfeo_dvec *sz_t, int zi_t); -// z <= beta * y + alpha * A * x, where A is symmetric and only the lower triangular patr of A is accessed -void blasfeo_ref_dsymv_l(int m, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -void blasfeo_ref_dsymv_l_mn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// z <= beta * y + alpha * A * x, where A is symmetric and only the upper triangular patr of A is accessed -void blasfeo_ref_dsymv_u(int m, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// D = C + alpha * x * y^T -void blasfeo_ref_dger(int m, int n, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); - -// diagonal - -// z <= beta * y + alpha * A * x, A diagonal -void blasfeo_ref_dgemv_d(int m, double alpha, struct blasfeo_dvec *sA, int ai, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); - - - -// -// level 3 BLAS -// - -// dense - -// D <= beta * C + alpha * A * B -void blasfeo_ref_dgemm_nn(int m, int n, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T -void blasfeo_ref_dgemm_nt(int m, int n, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B -void blasfeo_ref_dgemm_tn(int m, int n, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B^T -void blasfeo_ref_dgemm_tt(int m, int n, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T ; C, D lower triangular -void blasfeo_ref_dsyrk_ln(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -void blasfeo_ref_dsyrk_ln_mn(int m, int n, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B ; C, D lower triangular -void blasfeo_ref_dsyrk_lt(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T ; C, D upper triangular -void blasfeo_ref_dsyrk_un(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B ; C, D upper triangular -void blasfeo_ref_dsyrk_ut(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A * B ; A lower triangular -void blasfeo_ref_dtrmm_llnn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A * B ; A lower triangular -void blasfeo_ref_dtrmm_llnu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^T * B ; A lower triangular -void blasfeo_ref_dtrmm_lltn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^T * B ; A lower triangular -void blasfeo_ref_dtrmm_lltu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A * B ; A upper triangular -void blasfeo_ref_dtrmm_lunn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A * B ; A upper triangular -void blasfeo_ref_dtrmm_lunu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^T * B ; A upper triangular -void blasfeo_ref_dtrmm_lutn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^T * B ; A upper triangular -void blasfeo_ref_dtrmm_lutu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A ; A lower triangular -void blasfeo_ref_dtrmm_rlnn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A ; A lower triangular -void blasfeo_ref_dtrmm_rlnu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^T ; A lower triangular -void blasfeo_ref_dtrmm_rltn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^T ; A lower triangular -void blasfeo_ref_dtrmm_rltu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A ; A upper triangular -void blasfeo_ref_dtrmm_runn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A ; A upper triangular -void blasfeo_ref_dtrmm_runu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^T ; A upper triangular -void blasfeo_ref_dtrmm_rutn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^T ; A upper triangular -void blasfeo_ref_dtrmm_rutu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A lower triangular employint explicit inverse of diagonal -void blasfeo_ref_dtrsm_llnn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A lower triangular with unit diagonal -void blasfeo_ref_dtrsm_llnu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A lower triangular employint explicit inverse of diagonal -void blasfeo_ref_dtrsm_lltn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A lower triangular with unit diagonal -void blasfeo_ref_dtrsm_lltu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A upper triangular employing explicit inverse of diagonal -void blasfeo_ref_dtrsm_lunn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A upper triangular withunit diagonal -void blasfeo_ref_dtrsm_lunu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A upper triangular employing explicit inverse of diagonal -void blasfeo_ref_dtrsm_lutn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A upper triangular withunit diagonal -void blasfeo_ref_dtrsm_lutu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A lower triangular employing explicit inverse of diagonal -void blasfeo_ref_dtrsm_rlnn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A lower triangular with unit diagonal -void blasfeo_ref_dtrsm_rlnu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A lower triangular employing explicit inverse of diagonal -void blasfeo_ref_dtrsm_rltn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A lower triangular with unit diagonal -void blasfeo_ref_dtrsm_rltu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A upper triangular employing explicit inverse of diagonal -void blasfeo_ref_dtrsm_runn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A upper triangular with unit diagonal -void blasfeo_ref_dtrsm_runu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A upper triangular employing explicit inverse of diagonal -void blasfeo_ref_dtrsm_rutn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A upper triangular with unit diagonal -void blasfeo_ref_dtrsm_rutu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T + alpha * B * A^T ; C, D lower triangular -void blasfeo_ref_dsyr2k_ln(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B + alpha * B^T * A ; C, D lower triangular -void blasfeo_ref_dsyr2k_lt(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T + alpha * B * A^T ; C, D upper triangular -void blasfeo_ref_dsyr2k_un(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B + alpha * B^T * A ; C, D upper triangular -void blasfeo_ref_dsyr2k_ut(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); - -// diagonal - -// D <= alpha * A * B + beta * C, with A diagonal (stored as strvec) -void dgemm_diag_left_lib(int m, int n, double alpha, double *dA, double *pB, int sdb, double beta, double *pC, int sdc, double *pD, int sdd); -void blasfeo_ref_dgemm_dn(int m, int n, double alpha, struct blasfeo_dvec *sA, int ai, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A * B + beta * C, with B diagonal (stored as strvec) -void blasfeo_ref_dgemm_nd(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sB, int bi, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); - - - -// -// LAPACK -// - -// D <= chol( C ) ; C, D lower triangular -void blasfeo_ref_dpotrf_l(int m, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -void blasfeo_ref_dpotrf_l_mn(int m, int n, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= chol( C ) ; C, D upper triangular -void blasfeo_ref_dpotrf_u(int m, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= chol( C + A * B' ) ; C, D lower triangular -void blasfeo_ref_dsyrk_dpotrf_ln(int m, int k, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -void blasfeo_ref_dsyrk_dpotrf_ln_mn(int m, int n, int k, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= lu( C ) ; no pivoting -void blasfeo_ref_dgetrf_np(int m, int n, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= lu( C ) ; row pivoting -void blasfeo_ref_dgetrf_rp(int m, int n, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj, int *ipiv); -// D <= qr( C ) -int blasfeo_ref_dgeqrf_worksize(int m, int n); // in bytes -void blasfeo_ref_dgeqrf(int m, int n, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj, void *work); -// D <= Q factor, where C is the output of the LQ factorization -int blasfeo_ref_dorglq_worksize(int m, int n, int k); // in bytes -void blasfeo_ref_dorglq(int m, int n, int k, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj, void *work); -// D <= lq( C ) -void blasfeo_ref_dgelqf(int m, int n, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj, void *work); -int blasfeo_ref_dgelqf_worksize(int m, int n); // in bytes -// D <= lq( C ), positive diagonal elements -void blasfeo_ref_dgelqf_pd(int m, int n, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj, void *work); -// [L, A] <= lq( [L, A] ), positive diagonal elements, array of matrices, with -// L lower triangular, of size (m)x(m) -// A full, of size (m)x(n1) -void blasfeo_ref_dgelqf_pd_la(int m, int n1, struct blasfeo_dmat *sL, int li, int lj, struct blasfeo_dmat *sA, int ai, int aj, void *work); -// [L, L, A] <= lq( [L, L, A] ), positive diagonal elements, array of matrices, with: -// L lower triangular, of size (m)x(m) -// A full, of size (m)x(n1) -void blasfeo_ref_dgelqf_pd_lla(int m, int n1, struct blasfeo_dmat *sL0, int l0i, int l0j, struct blasfeo_dmat *sL1, int l1i, int l1j, struct blasfeo_dmat *sA, int ai, int aj, void *work); - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_D_BLASFEO_REF_API_H_ - diff --git a/third_party/acados/include/blasfeo/include/blasfeo_d_kernel.h b/third_party/acados/include/blasfeo/include/blasfeo_d_kernel.h deleted file mode 100644 index d20ac38bbd..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_d_kernel.h +++ /dev/null @@ -1,1321 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_D_KERNEL_H_ -#define BLASFEO_D_KERNEL_H_ - - - -#include "blasfeo_target.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// utils -void blasfeo_align_2MB(void *ptr, void **ptr_align); -void blasfeo_align_4096_byte(void *ptr, void **ptr_align); -void blasfeo_align_64_byte(void *ptr, void **ptr_align); - - -// -// lib8 -// - -// 24x8 -void kernel_dgemm_nt_24x8_lib8(int k, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nt_24x8_vs_lib8(int k, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dtrsm_nt_rl_inv_24x8_lib8(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E); // -void kernel_dpotrf_nt_l_24x8_lib8(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dpotrf_nt_l_24x8_vs_lib8(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int m1, int n1); -void kernel_dtrsm_nt_rl_inv_24x8_vs_lib8(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E, int m1, int n1); // -void kernel_dgemm_dtrsm_nt_rl_inv_24x8_lib8(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E); -void kernel_dgemm_dtrsm_nt_rl_inv_24x8_vs_lib8(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E, int m1, int n1); -void kernel_dsyrk_dpotrf_nt_l_24x8_lib8(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dsyrk_dpotrf_nt_l_24x8_vs_lib8(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int m1, int n1); -void kernel_dlarfb8_rn_24_lib8(int kmax, double *pV, double *pT, double *pD, int sdd); -// 16x8 -void kernel_dgemm_nt_16x8_lib8(int k, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nt_16x8_vs_lib8(int k, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dgemm_nt_16x8_gen_lib8(int k, double *alpha, double *A, int sda, double *B, double *beta, int offC, double *C, int sdc, int offD, double *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_dgemm_nn_16x8_lib8(int k, double *alpha, double *A, int sda, int offB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nn_16x8_vs_lib8(int k, double *alpha, double *A, int sda, int offB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dgemm_nn_16x8_gen_lib8(int k, double *alpha, double *A, int sda, int offB, double *B, int sdb, double *beta, int offC, double *C, int sdc, int offD, double *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_dsyrk_nt_l_16x8_lib8(int k, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dsyrk_nt_l_16x8_vs_lib8(int k, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dsyrk_nt_l_16x8_gen_lib8(int k, double *alpha, double *A, int sda, double *B, double *beta, int offC, double *C, int sdc, int offD, double *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_dtrmm_nn_rl_16x8_lib8(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *D, int sdd); -void kernel_dtrmm_nn_rl_16x8_vs_lib8(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *D, int sdd, int m1, int n1); -void kernel_dtrmm_nn_rl_16x8_gen_lib8(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, int offD, double *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_dtrsm_nt_rl_inv_16x8_lib8(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E); // -void kernel_dtrsm_nt_rl_inv_16x8_vs_lib8(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E, int m1, int n1); // -void kernel_dpotrf_nt_l_16x8_lib8(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dpotrf_nt_l_16x8_vs_lib8(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int m1, int n1); -void kernel_dgemm_dtrsm_nt_rl_inv_16x8_lib8(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E); -void kernel_dgemm_dtrsm_nt_rl_inv_16x8_vs_lib8(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E, int m1, int n1); -void kernel_dsyrk_dpotrf_nt_l_16x8_lib8(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dsyrk_dpotrf_nt_l_16x8_vs_lib8(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int m1, int n1); -void kernel_dlarfb8_rn_16_lib8(int kmax, double *pV, double *pT, double *pD, int sdd); -void kernel_dlarfb8_rn_la_16_lib8(int n1, double *pVA, double *pT, double *pD, int sdd, double *pA, int sda); -void kernel_dlarfb8_rn_lla_16_lib8(int n0, int n1, double *pVL, double *pVA, double *pT, double *pD, int sdd, double *pL, int sdl, double *pA, int sda); -// 8x16 -void kernel_dgemm_tt_8x16_lib8(int k, double *alpha, int offA, double *A, int sda, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dgemm_tt_8x16_vs_lib8(int k, double *alpha, int offA, double *A, int sda, double *B, int sdb, double *beta, double *C, double *D, int m1, int n1); // -void kernel_dgemm_tt_8x16_gen_lib8(int k, double *alpha, int offA, double *A, int sda, double *B, int sdb, double *beta, int offC, double *C, int sdc, int offD, double *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_dgemm_nt_8x16_lib8(int k, double *alpha, double *A, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dgemm_nt_8x16_vs_lib8(int k, double *alpha, double *A, double *B, int sdb, double *beta, double *C, double *D, int m1, int n1); // -// 8x8 -void kernel_dgemm_nt_8x8_lib8(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D); // -void kernel_dgemm_nt_8x8_vs_lib8(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D, int m1, int n1); // -void kernel_dgemm_nt_8x8_gen_lib8(int k, double *alpha, double *A, double *B, double *beta, int offC, double *C, int sdc, int offD, double *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_dgemm_nn_8x8_lib8(int k, double *alpha, double *A, int offB, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dgemm_nn_8x8_vs_lib8(int k, double *alpha, double *A, int offB, double *B, int sdb, double *beta, double *C, double *D, int m1, int n1); // -void kernel_dgemm_nn_8x8_gen_lib8(int k, double *alpha, double *A, int offB, double *B, int sdb, double *beta, int offC, double *C, int sdc, int offD, double *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_dgemm_tt_8x8_lib8(int k, double *alpha, int offA, double *A, int sda, double *B, double *beta, double *C, double *D); // -void kernel_dgemm_tt_8x8_vs_lib8(int k, double *alpha, int offA, double *A, int sda, double *B, double *beta, double *C, double *D, int m1, int n1); // -void kernel_dgemm_tt_8x8_gen_lib8(int k, double *alpha, int offA, double *A, int sda, double *B, double *beta, int offc, double *C, int sdc, int offD, double *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_dsyrk_nt_l_8x8_lib8(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D); // -void kernel_dsyrk_nt_l_8x8_vs_lib8(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D, int m1, int n1); // -void kernel_dsyrk_nt_l_8x8_gen_lib8(int k, double *alpha, double *A, double *B, double *beta, int offC, double *C, int sdc, int offD, double *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_dtrmm_nn_rl_8x8_lib8(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *D); -void kernel_dtrmm_nn_rl_8x8_vs_lib8(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *D, int m1, int n1); -void kernel_dtrmm_nn_rl_8x8_gen_lib8(int k, double *alpha, double *A, int offsetB, double *B, int sdb, int offD, double *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_dtrsm_nt_rl_inv_8x8_lib8(int k, double *A, double *B, double *beta, double *C, double *D, double *E, double *inv_diag_E); -void kernel_dtrsm_nt_rl_inv_8x8_vs_lib8(int k, double *A, double *B, double *beta, double *C, double *D, double *E, double *inv_diag_E, int m1, int n1); -void kernel_dpotrf_nt_l_8x8_lib8(int k, double *A, double *B, double *C, double *D, double *inv_diag_D); -void kernel_dpotrf_nt_l_8x8_vs_lib8(int k, double *A, double *B, double *C, double *D, double *inv_diag_D, int m1, int n1); -void kernel_dgemm_dtrsm_nt_rl_inv_8x8_lib8(int kp, double *Ap, double *Bp, int km_, double *Am, double *Bm, double *C, double *D, double *E, double *inv_diag_E); -void kernel_dgemm_dtrsm_nt_rl_inv_8x8_vs_lib8(int kp, double *Ap, double *Bp, int km_, double *Am, double *Bm, double *C, double *D, double *E, double *inv_diag_E, int m1, int n1); -void kernel_dsyrk_dpotrf_nt_l_8x8_lib8(int kp, double *Ap, double *Bp, int km_, double *Am, double *Bm, double *C, double *D, double *inv_diag_D); -void kernel_dsyrk_dpotrf_nt_l_8x8_vs_lib8(int kp, double *Ap, double *Bp, int km_, double *Am, double *Bm, double *C, double *D, double *inv_diag_D, int m1, int n1); -void kernel_dgelqf_vs_lib8(int m, int n, int k, int offD, double *pD, int sdd, double *dD); -void kernel_dgelqf_pd_vs_lib8(int m, int n, int k, int offD, double *pD, int sdd, double *dD); -void kernel_dgelqf_8_lib8(int kmax, double *pD, double *dD); -void kernel_dgelqf_pd_8_lib8(int kmax, double *pD, double *dD); -void kernel_dlarft_8_lib8(int kmax, double *pD, double *dD, double *pT); -void kernel_dlarfb8_rn_8_lib8(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb8_rn_8_vs_lib8(int kmax, double *pV, double *pT, double *pD, int m1); -void kernel_dlarfb8_rn_1_lib8(int kmax, double *pV, double *pT, double *pD); -void kernel_dgelqf_dlarft8_8_lib8(int kmax, double *pD, double *dD, double *pT); -void kernel_dgelqf_pd_dlarft8_8_lib8(int kmax, double *pD, double *dD, double *pT); -void kernel_dgelqf_pd_la_vs_lib8(int m, int n1, int k, int offD, double *pD, int sdd, double *dD, int offA, double *pA, int sda); -void kernel_dgelqf_pd_la_dlarft8_8_lib8(int kmax, double *pD, double *dD, double *pA, double *pT); -void kernel_dlarft_la_8_lib8(int n1, double *dD, double *pA, double *pT); -void kernel_dlarfb8_rn_la_8_lib8(int n1, double *pVA, double *pT, double *pD, double *pA); -void kernel_dlarfb8_rn_la_8_vs_lib8(int n1, double *pVA, double *pT, double *pD, double *pA, int m1); -void kernel_dlarfb8_rn_la_1_lib8(int n1, double *pVA, double *pT, double *pD, double *pA); -void kernel_dgelqf_pd_lla_vs_lib8(int m, int n0, int n1, int k, int offD, double *pD, int sdd, double *dD, int offL, double *pL, int sdl, int offA, double *pA, int sda); -void kernel_dgelqf_pd_lla_dlarft8_8_lib8(int n0, int n1, double *pD, double *dD, double *pL, double *pA, double *pT); -void kernel_dlarft_lla_8_lib8(int n0, int n1, double *dD, double *pL, double *pA, double *pT); -void kernel_dlarfb8_rn_lla_8_lib8(int n0, int n1, double *pVL, double *pVA, double *pT, double *pD, double *pL, double *pA); -void kernel_dlarfb8_rn_lla_8_vs_lib8(int n0, int n1, double *pVL, double *pVA, double *pT, double *pD, double *pL, double *pA, int m1); -void kernel_dlarfb8_rn_lla_1_lib8(int n0, int n1, double *pVL, double *pVA, double *pT, double *pD, double *pL, double *pA); - -// panel copy / pack -// 24 -void kernel_dpack_nn_24_lib8(int kmax, double *A, int lda, double *C, int sdc); -void kernel_dpack_nn_24_vs_lib8(int kmax, double *A, int lda, double *C, int sdc, int m1); -// 16 -void kernel_dpacp_nn_16_lib8(int kmax, int offsetA, double *A, int sda, double *B, int sdb); -void kernel_dpacp_nn_16_vs_lib8(int kmax, int offsetA, double *A, int sda, double *B, int sdb, int m1); -void kernel_dpack_nn_16_lib8(int kmax, double *A, int lda, double *C, int sdc); -void kernel_dpack_nn_16_vs_lib8(int kmax, double *A, int lda, double *C, int sdc, int m1); -// 8 -void kernel_dpacp_nn_8_lib8(int kmax, int offsetA, double *A, int sda, double *B); -void kernel_dpacp_nn_8_vs_lib8(int kmax, int offsetA, double *A, int sda, double *B, int m1); -void kernel_dpacp_tn_8_lib8(int kmax, int offsetA, double *A, int sda, double *B); -void kernel_dpacp_tn_8_vs_lib8(int kmax, int offsetA, double *A, int sda, double *B, int m1); -void kernel_dpacp_l_nn_8_lib8(int kmax, int offsetA, double *A, int sda, double *B); -void kernel_dpacp_l_nn_8_vs_lib8(int kmax, int offsetA, double *A, int sda, double *B, int m1); -void kernel_dpacp_l_tn_8_lib8(int kmax, int offsetA, double *A, int sda, double *B); -void kernel_dpacp_l_tn_8_vs_lib8(int kmax, int offsetA, double *A, int sda, double *B, int m1); -void kernel_dpaad_nn_8_lib8(int kmax, double *alpha, int offsetA, double *A, int sda, double *B); -void kernel_dpaad_nn_8_vs_lib8(int kmax, double *alpha, int offsetA, double *A, int sda, double *B, int m1); -void kernel_dpack_nn_8_lib8(int kmax, double *A, int lda, double *C); -void kernel_dpack_nn_8_vs_lib8(int kmax, double *A, int lda, double *C, int m1); -void kernel_dpack_tn_8_lib8(int kmax, double *A, int lda, double *C); -void kernel_dpack_tn_8_vs_lib8(int kmax, double *A, int lda, double *C, int m1); -// 4 -void kernel_dpack_tt_4_lib8(int kmax, double *A, int lda, double *C, int sdc); // TODO offsetC -void kernel_dpack_tt_4_vs_lib8(int kmax, double *A, int lda, double *C, int sdc, int m1); // TODO offsetC - -// level 2 BLAS -// 16 -void kernel_dgemv_n_16_lib8(int k, double *alpha, double *A, int sda, double *x, double *beta, double *y, double *z); -// 8 -void kernel_dgemv_n_8_lib8(int k, double *alpha, double *A, double *x, double *beta, double *y, double *z); -void kernel_dgemv_n_8_vs_lib8(int k, double *alpha, double *A, double *x, double *beta, double *y, double *z, int m1); -//void kernel_dgemv_n_8_gen_lib8(int k, double *alpha, double *A, double *x, double *beta, double *y, double *z, int m0, int m1); -void kernel_dgemv_n_8_gen_lib8(int k, double *alpha, int offsetA, double *A, double *x, double *beta, double *y, double *z, int m1); -void kernel_dgemv_t_8_lib8(int k, double *alpha, int offsetA, double *A, int sda, double *x, double *beta, double *y, double *z); -void kernel_dgemv_t_8_vs_lib8(int k, double *alpha, int offsetA, double *A, int sda, double *x, double *beta, double *y, double *z, int n1); -void kernel_dgemv_nt_8_lib8(int kmax, double *alpha_n, double *alpha_t, int offsetA, double *A, int sda, double *x_n, double *x_t, double *beta_t, double *y_t, double *z_n, double *z_t); -void kernel_dgemv_nt_8_vs_lib8(int kmax, double *alpha_n, double *alpha_t, int offsetA, double *A, int sda, double *x_n, double *x_t, double *beta_t, double *y_t, double *z_n, double *z_t, int n1); -void kernel_dsymv_l_8_lib8(int kmax, double *alpha, double *A, int sda, double *x, double *z); -void kernel_dsymv_l_8_vs_lib8(int kmax, double *alpha, double *A, int sda, double *x, double *z, int n1); -void kernel_dsymv_l_8_gen_lib8(int kmax, double *alpha, int offsetA, double *A, int sda, double *x, double *z, int n1); -void kernel_dtrmv_n_ln_8_lib8(int k, double *A, double *x, double *z); -void kernel_dtrmv_n_ln_8_vs_lib8(int k, double *A, double *x, double *z, int m1); -void kernel_dtrmv_n_ln_8_gen_lib8(int k, int offsetA, double *A, double *x, double *z, int m1); -void kernel_dtrmv_t_ln_8_lib8(int k, double *A, int sda, double *x, double *z); -void kernel_dtrmv_t_ln_8_vs_lib8(int k, double *A, int sda, double *x, double *z, int n1); -void kernel_dtrmv_t_ln_8_gen_lib8(int k, int offsetA, double *A, int sda, double *x, double *z, int n1); -void kernel_dtrsv_n_l_inv_8_lib8(int k, double *A, double *inv_diag_A, double *x, double *z); -void kernel_dtrsv_n_l_inv_8_vs_lib8(int k, double *A, double *inv_diag_A, double *x, double *z, int m1, int n1); -void kernel_dtrsv_t_l_inv_8_lib8(int k, double *A, int sda, double *inv_diag_A, double *x, double *z); -void kernel_dtrsv_t_l_inv_8_vs_lib8(int k, double *A, int sda, double *inv_diag_A, double *x, double *z, int m1, int n1); - - - -// -// lib4 -// - -// level 2 BLAS -// 12 -void kernel_dgemv_n_12_lib4(int k, double *alpha, double *A, int sda, double *x, double *beta, double *y, double *z); -void kernel_dgemv_t_12_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *x, double *beta, double *y, double *z); -// 8 -void kernel_dgemv_n_8_lib4(int k, double *alpha, double *A, int sda, double *x, double *beta, double *y, double *z); -void kernel_dgemv_t_8_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *x, double *beta, double *y, double *z); -void kernel_dtrmv_un_8_lib4(int k, double *A, int sda, double *x, double *z); -// 4 -void kernel_dgemv_n_4_lib4(int k, double *alpha, double *A, double *x, double *beta, double *y, double *z); -void kernel_dgemv_n_4_vs_lib4(int k, double *alpha, double *A, double *x, double *beta, double *y, double *z, int k1); -void kernel_dgemv_n_4_gen_lib4(int kmax, double *alpha, double *A, double *x, double *beta, double *y, double *z, int k0, int k1); -void kernel_dgemv_t_4_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *x, double *beta, double *y, double *z); -void kernel_dgemv_t_4_vs_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *x, double *beta, double *y, double *z, int k1); -void kernel_dtrsv_ln_inv_4_lib4(int k, double *A, double *inv_diag_A, double *x, double *y, double *z); -void kernel_dtrsv_ln_inv_4_vs_lib4(int k, double *A, double *inv_diag_A, double *x, double *y, double *z, int km, int kn); -void kernel_dtrsv_lt_inv_4_lib4(int k, double *A, int sda, double *inv_diag_A, double *x, double *y, double *z); -void kernel_dtrsv_lt_inv_3_lib4(int k, double *A, int sda, double *inv_diag_A, double *x, double *y, double *z); -void kernel_dtrsv_lt_inv_2_lib4(int k, double *A, int sda, double *inv_diag_A, double *x, double *y, double *z); -void kernel_dtrsv_lt_inv_1_lib4(int k, double *A, int sda, double *inv_diag_A, double *x, double *y, double *z); -void kernel_dtrsv_lt_one_4_lib4(int k, double *A, int sda, double *x, double *y, double *z); -void kernel_dtrsv_lt_one_3_lib4(int k, double *A, int sda, double *x, double *y, double *z); -void kernel_dtrsv_lt_one_2_lib4(int k, double *A, int sda, double *x, double *y, double *z); -void kernel_dtrsv_lt_one_1_lib4(int k, double *A, int sda, double *x, double *y, double *z); -void kernel_dtrsv_ln_one_4_vs_lib4(int kmax, double *A, double *x, double *y, double *z, int km, int kn); -void kernel_dtrsv_ln_one_4_lib4(int kmax, double *A, double *x, double *y, double *z); -void kernel_dtrsv_un_inv_4_lib4(int kmax, double *A, double *inv_diag_A, double *x, double *y, double *z); -void kernel_dtrsv_ut_inv_4_lib4(int kmax, double *A, int sda, double *inv_diag_A, double *x, double *y, double *z); -void kernel_dtrsv_ut_inv_4_vs_lib4(int kmax, double *A, int sda, double *inv_diag_A, double *x, double *y, double *z, int m1, int n1); -void kernel_dtrmv_un_4_lib4(int k, double *A, double *x, double *z); -void kernel_dtrmv_ut_4_lib4(int k, double *A, int sda, double *x, double *z); -void kernel_dtrmv_ut_4_vs_lib4(int k, double *A, int sda, double *x, double *z, int km); -void kernel_dgemv_nt_6_lib4(int kmax, double *alpha_n, double *alpha_t, double *A, int sda, double *x_n, double *x_t, double *beta_t, double *y_t, double *z_n, double *z_t); -void kernel_dgemv_nt_4_lib4(int kmax, double *alpha_n, double *alpha_t, double *A, int sda, double *x_n, double *x_t, double *beta_t, double *y_t, double *z_n, double *z_t); -void kernel_dgemv_nt_4_vs_lib4(int kmax, double *alpha_n, double *alpha_t, double *A, int sda, double *x_n, double *x_t, double *beta_t, double *y_t, double *z_n, double *z_t, int km); -void kernel_dsymv_l_4_lib4(int kmax, double *alpha, double *A, int sda, double *x, double *z); -void kernel_dsymv_l_4_gen_lib4(int kmax, double *alpha, int offA, double *A, int sda, double *x, double *z, int km); - - - -// level 3 BLAS -// 12x4 -void kernel_dgemm_nt_12x4_lib4(int k, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nt_12x4_vs_lib4(int k, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, int km, int kn); // -void kernel_dgemm_nt_12x4_gen_lib4(int k, double *alpha, double *A, int sda, double *B, double *beta, int offsetC, double *C, int sdc, int offsetD, double *D, int sdd, int m0, int m1, int k0, int k1); -void kernel_dgemm_nn_12x4_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nn_12x4_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int km, int kn); // -void kernel_dgemm_nn_12x4_gen_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, int offsetC, double *C, int sdc, int offsetD, double *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_dgemm_tt_12x4_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_tt_12x4_vs_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dsyrk_nn_u_12x4_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dsyrk_nn_u_12x4_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dsyrk_nt_l_12x4_lib4(int k, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dsyrk_nt_l_12x4_vs_lib4(int k, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, int km, int kn); // -void kernel_dtrmm_nt_ru_12x4_lib4(int k, double *alpha, double *A, int sda, double *B, double *D, int sdd); // -void kernel_dtrmm_nt_ru_12x4_vs_lib4(int k, double *alpha, double *A, int sda, double *B, double *D, int sdd, int km, int kn); // -void kernel_dtrmm_nn_rl_12x4_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *D, int sdd); -void kernel_dtrmm_nn_rl_12x4_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *D, int sdd, int km, int kn); -void kernel_dtrsm_nt_rl_inv_12x4_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E); -void kernel_dtrsm_nt_rl_inv_12x4_vs_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nt_rl_one_12x4_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E); -void kernel_dtrsm_nt_rl_one_12x4_vs_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, int km, int kn); -void kernel_dtrsm_nt_ru_inv_12x4_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E); -void kernel_dtrsm_nt_ru_inv_12x4_vs_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nt_ru_one_12x4_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E); -void kernel_dtrsm_nt_ru_one_12x4_vs_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, int km, int kn); -void kernel_dtrsm_nn_ru_inv_12x4_lib4(int k, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E); -void kernel_dtrsm_nn_ru_inv_12x4_vs_lib4(int k, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nn_ll_inv_12x4_lib4(int k, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int sde, double *inv_diag_E); -void kernel_dtrsm_nn_ll_inv_12x4_vs_lib4(int k, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int sde, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nn_ll_one_12x4_lib4(int k, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int sde); -void kernel_dtrsm_nn_ll_one_12x4_vs_lib4(int k, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int sde, int km, int kn); -void kernel_dtrsm_nn_lu_inv_12x4_lib4(int kmax, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *E, int sde, double *inv_diag_E); -void kernel_dtrsm_nn_lu_inv_12x4_vs_lib4(int kmax, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *E, int sde, double *inv_diag_E, int km, int kn); -// 4x12 -void kernel_dgemm_nt_4x12_lib4(int k, double *alpha, double *A, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dgemm_nt_4x12_vs_lib4(int k, double *alpha, double *A, double *B, int sdb, double *beta, double *C, double *D, int km, int kn); // -void kernel_dgemm_nn_4x12_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dgemm_nn_4x12_vs_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D, int m1, int n1); // -void kernel_dgemm_tt_4x12_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dgemm_tt_4x12_vs_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *B, int sdb, double *beta, double *C, double *D, int m1, int n1); // -void kernel_dgemm_tt_4x12_gen_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *B, int sdb, double *beta, int offsetC, double *C, int sdc, int offsetD, double *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_dtrsm_nt_rl_inv_4x12_lib4(int k, double *A, double *B, int sdb, double *C, double *D, double *E, int sed, double *inv_diag_E); -void kernel_dtrsm_nt_rl_inv_4x12_vs_lib4(int k, double *A, double *B, int sdb, double *C, double *D, double *E, int sed, double *inv_diag_E, int km, int kn); -// 8x8 -void kernel_dgemm_nt_8x8l_lib4(int k, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // computes [A00 *; A10 A11] -void kernel_dgemm_nt_8x8u_lib4(int k, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // computes [A00 *; A10 A11] -void kernel_dgemm_nt_8x8l_vs_lib4(int k, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int km, int kn); // computes [A00 *; A10 A11] -void kernel_dgemm_nt_8x8u_vs_lib4(int k, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int km, int kn); // computes [A00 *; A10 A11] -void kernel_dsyrk_nn_u_8x8_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dsyrk_nn_u_8x8_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dsyrk_nt_l_8x8_lib4(int k, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // computes [L00 *; A10 L11] -void kernel_dsyrk_nt_l_8x8_vs_lib4(int k, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int km, int kn); // computes [L00 *; A10 L11] -void kernel_dtrsm_nt_rl_inv_8x8l_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *E, int sed, double *inv_diag_E); -void kernel_dtrsm_nt_rl_inv_8x8l_vs_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *E, int sed, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nt_rl_inv_8x8u_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *E, int sed, double *inv_diag_E); -void kernel_dtrsm_nt_rl_inv_8x8u_vs_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *E, int sed, double *inv_diag_E, int km, int kn); -// 8x4 -void kernel_dgemm_nt_8x4_lib4(int k, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nt_8x4_vs_lib4(int k, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, int km, int kn); // -void kernel_dgemm_nt_8x4_gen_lib4(int k, double *alpha, double *A, int sda, double *B, double *beta, int offsetC, double *C, int sdc, int offsetD, double *D, int sdd, int m0, int m1, int k0, int k1); -void kernel_dgemm_nn_8x4_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nn_8x4_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dgemm_nn_8x4_gen_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, int offsetC, double *C, int sdc, int offsetD, double *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_dgemm_tt_8x4_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_tt_8x4_vs_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dsyrk_nn_u_8x4_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dsyrk_nn_u_8x4_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dsyrk_nt_l_8x4_lib4(int k, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dsyrk_nt_l_8x4_vs_lib4(int k, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, int km, int kn); // -void kernel_dsyrk_nt_l_8x4_gen_lib4(int k, double *alpha, double *A, int sda, double *B, double *beta, int offsetC, double *C, int sdc, int offsetD, double *D, int sdd, int m0, int m1, int k0, int k1); -void kernel_dtrmm_nt_ru_8x4_lib4(int k, double *alpha, double *A, int sda, double *B, double *D, int sdd); // -void kernel_dtrmm_nt_ru_8x4_vs_lib4(int k, double *alpha, double *A, int sda, double *B, double *D, int sdd, int km, int kn); // -void kernel_dtrmm_nn_rl_8x4_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *D, int sdd); -void kernel_dtrmm_nn_rl_8x4_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *D, int sdd, int km, int kn); -void kernel_dtrmm_nn_rl_8x4_gen_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, int offsetD, double *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_dtrsm_nt_rl_inv_8x4_vs_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nt_rl_inv_8x4_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E); -void kernel_dtrsm_nt_rl_one_8x4_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E); -void kernel_dtrsm_nt_rl_one_8x4_vs_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, int km, int kn); -void kernel_dtrsm_nt_ru_inv_8x4_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E); -void kernel_dtrsm_nt_ru_inv_8x4_vs_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nt_ru_one_8x4_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E); -void kernel_dtrsm_nt_ru_one_8x4_vs_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, int km, int kn); -void kernel_dtrsm_nn_ru_inv_8x4_lib4(int k, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E); -void kernel_dtrsm_nn_ru_inv_8x4_vs_lib4(int k, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nn_ll_inv_8x4_lib4(int k, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int sde, double *inv_diag_E); -void kernel_dtrsm_nn_ll_inv_8x4_vs_lib4(int k, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int sde, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nn_ll_one_8x4_lib4(int k, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int sde); -void kernel_dtrsm_nn_ll_one_8x4_vs_lib4(int k, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int sde, int km, int kn); -void kernel_dtrsm_nn_lu_inv_8x4_lib4(int kmax, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *E, int sde, double *inv_diag_E); -void kernel_dtrsm_nn_lu_inv_8x4_vs_lib4(int kmax, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *E, int sde, double *inv_diag_E, int km, int kn); -// 4x8 -void kernel_dgemm_nt_4x8_lib4(int k, double *alpha, double *A, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dgemm_nt_4x8_vs_lib4(int k, double *alpha, double *A, double *B, int sdb, double *beta, double *C, double *D, int km, int kn); // -void kernel_dgemm_nn_4x8_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dgemm_nn_4x8_vs_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D, int m1, int n1); // -void kernel_dgemm_tt_4x8_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dgemm_tt_4x8_vs_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *B, int sdb, double *beta, double *C, double *D, int m1, int n1); // -void kernel_dgemm_tt_4x8_gen_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *B, int sdb, double *beta, int offsetC, double *C, int sdc, int offsetD, double *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_dtrsm_nt_rl_inv_4x8_lib4(int k, double *A, double *B, int sdb, double *C, double *D, double *E, int sed, double *inv_diag_E); -void kernel_dtrsm_nt_rl_inv_4x8_vs_lib4(int k, double *A, double *B, int sdb, double *C, double *D, double *E, int sed, double *inv_diag_E, int km, int kn); -// 8x2 -void kernel_dgemm_nn_8x2_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nn_8x2_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -// 2x8 -void kernel_dgemm_nn_2x8_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dgemm_nn_2x8_vs_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D, int m1, int n1); // -// 10xX -void kernel_dgemm_nn_10x4_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nn_10x4_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dgemm_nn_10x2_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nn_10x2_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -// 6xX -void kernel_dgemm_nn_8x6_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nn_8x6_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dgemm_nn_6x8_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nn_6x8_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dgemm_nn_6x6_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nn_6x6_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dgemm_nn_6x4_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nn_6x4_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dgemm_nn_6x2_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nn_6x2_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -// 4x4 -void kernel_dgemm_nt_4x4_lib4(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D); // -void kernel_dgemm_nt_4x4_vs_lib4(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D, int km, int kn); // -void kernel_dgemm_nt_4x4_gen_lib4(int k, double *alpha, double *A, double *B, double *beta, int offsetC, double *C, int sdc, int offsetD, double *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_dgemm_nn_4x4_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dgemm_nn_4x4_vs_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D, int m1, int n1); // -void kernel_dgemm_nn_4x4_gen_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, int offsetC, double *C, int sdc, int offsetD, double *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_dgemm_tt_4x4_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *B, double *beta, double *C, double *D); // -void kernel_dgemm_tt_4x4_vs_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *B, double *beta, double *C, double *D, int m1, int n1); // -void kernel_dgemm_tt_4x4_gen_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *B, double *beta, int offsetC, double *C, int sdc, int offsetD, double *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_dsyrk_nn_u_4x4_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dsyrk_nn_u_4x4_vs_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D, int m1, int n1); // -void kernel_dsyrk_nt_l_4x4_lib4(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D); // -void kernel_dsyrk_nt_l_4x4_vs_lib4(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D, int km, int kn); // -void kernel_dsyrk_nt_l_4x4_gen_lib4(int k, double *alpha, double *A, double *B, double *beta, int offsetC, double *C, int sdc, int offsetD, double *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_dsyrk_nt_u_4x4_lib4(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D); // -void kernel_dsyrk_nt_u_4x4_vs_lib4(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D, int km, int kn); // -void kernel_dsyrk_nt_u_4x4_gen_lib4(int k, double *alpha, double *A, double *B, double *beta, int offsetC, double *C, int sdc, int offsetD, double *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_dtrmm_nt_ru_4x4_lib4(int k, double *alpha, double *A, double *B, double *D); // -void kernel_dtrmm_nt_ru_4x4_vs_lib4(int k, double *alpha, double *A, double *B, double *D, int km, int kn); // -void kernel_dtrmm_nn_rl_4x4_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *D); -void kernel_dtrmm_nn_rl_4x4_vs_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *D, int m1, int n1); -void kernel_dtrmm_nn_rl_4x4_gen_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, int offsetD, double *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_dtrsm_nt_rl_inv_4x4_lib4(int k, double *A, double *B, double *beta, double *C, double *D, double *E, double *inv_diag_E); -void kernel_dtrsm_nt_rl_inv_4x4_vs_lib4(int k, double *A, double *B, double *beta, double *C, double *D, double *E, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nt_rl_one_4x4_lib4(int k, double *A, double *B, double *beta, double *C, double *D, double *E); -void kernel_dtrsm_nt_rl_one_4x4_vs_lib4(int k, double *A, double *B, double *beta, double *C, double *D, double *E, int km, int kn); -void kernel_dtrsm_nt_ru_inv_4x4_lib4(int k, double *A, double *B, double *beta, double *C, double *D, double *E, double *inv_diag_E); -void kernel_dtrsm_nt_ru_inv_4x4_vs_lib4(int k, double *A, double *B, double *beta, double *C, double *D, double *E, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nt_ru_one_4x4_lib4(int k, double *A, double *B, double *beta, double *C, double *D, double *E); -void kernel_dtrsm_nt_ru_one_4x4_vs_lib4(int k, double *A, double *B, double *beta, double *C, double *D, double *E, int km, int kn); -void kernel_dtrsm_nn_ru_inv_4x4_lib4(int k, double *A, double *B, int sdb, double *beta, double *C, double *D, double *E, double *inv_diag_E); -void kernel_dtrsm_nn_ru_inv_4x4_vs_lib4(int k, double *A, double *B, int sdb, double *beta, double *C, double *D, double *E, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nn_ll_inv_4x4_lib4(int k, double *A, double *B, int sdb, double *beta, double *C, double *D, double *E, double *inv_diag_E); -void kernel_dtrsm_nn_ll_inv_4x4_vs_lib4(int k, double *A, double *B, int sdb, double *beta, double *C, double *D, double *E, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nn_ll_one_4x4_lib4(int k, double *A, double *B, int sdb, double *beta, double *C, double *D, double *E); -void kernel_dtrsm_nn_ll_one_4x4_vs_lib4(int k, double *A, double *B, int sdb, double *beta, double *C, double *D, double *E, int km, int kn); -void kernel_dtrsm_nn_lu_inv_4x4_lib4(int kmax, double *A, double *B, int sdb, double *C, double *D, double *E, double *inv_diag_E); -void kernel_dtrsm_nn_lu_inv_4x4_vs_lib4(int kmax, double *A, double *B, int sdb, double *C, double *D, double *E, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nn_lu_one_4x4_lib4(int kmax, double *A, double *B, int sdb, double *C, double *D, double *E); -void kernel_dtrsm_nn_lu_one_4x4_vs_lib4(int kmax, double *A, double *B, int sdb, double *C, double *D, double *E, int km, int kn); -// 4x2 -void kernel_dgemm_nn_4x2_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dgemm_nn_4x2_vs_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D, int m1, int n1); // -void kernel_dgemm_nt_4x2_lib4(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D); -void kernel_dgemm_nt_4x2_vs_lib4(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D, int m1, int n1); -void kernel_dsyrk_nt_l_4x2_lib4(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D); // -void kernel_dsyrk_nt_l_4x2_vs_lib4(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D, int km, int kn); // -void kernel_dtrmm_nn_rl_4x2_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *D); -void kernel_dtrmm_nn_rl_4x2_vs_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *D, int m1, int n1); -void kernel_dtrsm_nt_rl_inv_4x2_lib4(int k, double *A, double *B, double *beta, double *C, double *D, double *E, double *inv_diag_E); -void kernel_dtrsm_nt_rl_inv_4x2_vs_lib4(int k, double *A, double *B, double *beta, double *C, double *D, double *E, double *inv_diag_E, int km, int kn); -// 2x4 -void kernel_dgemm_nn_2x4_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dgemm_nn_2x4_vs_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D, int m1, int n1); // -// 2x2 -void kernel_dgemm_nn_2x2_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dsyrk_nt_l_2x2_lib4(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D); // -void kernel_dsyrk_nt_l_2x2_vs_lib4(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D, int km, int kn); // -// diag -void kernel_dgemm_diag_right_4_a0_lib4(int kmax, double *alpha, double *A, int sda, double *B, double *D, int sdd); -void kernel_dgemm_diag_right_4_lib4(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd); -void kernel_dgemm_diag_right_3_lib4(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd); -void kernel_dgemm_diag_right_2_lib4(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd); -void kernel_dgemm_diag_right_1_lib4(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd); -void kernel_dgemm_diag_left_4_a0_lib4(int kmax, double *alpha, double *A, double *B, double *D); -void kernel_dgemm_diag_left_4_lib4(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D); -void kernel_dgemm_diag_left_3_lib4(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D); -void kernel_dgemm_diag_left_2_lib4(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D); -void kernel_dgemm_diag_left_1_lib4(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D); -// low rank update -void kernel_dger4_sub_12r_lib4(int k, double *A, int sda, double *B, double *C, int sdc); -void kernel_dger4_sub_12r_vs_lib4(int k, double *A, int sda, double *B, double *C, int sdc, int km); -void kernel_dger4_sub_8r_lib4(int k, double *A, int sda, double *B, double *C, int sdc); -void kernel_dger4_sub_8r_vs_lib4(int k, double *A, int sda, double *B, double *C, int sdc, int km); -void kernel_dger4_sub_4r_lib4(int n, double *A, double *B, double *C); -void kernel_dger4_sub_4r_vs_lib4(int n, double *A, double *B, double *C, int km); - - - -// LAPACK -// 12x4 -void kernel_dpotrf_nt_l_12x4_lib4(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dpotrf_nt_l_12x4_vs_lib4(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -void kernel_dgetrf_nn_l_12x4_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dgetrf_nn_l_12x4_vs_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -void kernel_dgetrf_nn_m_12x4_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dgetrf_nn_m_12x4_vs_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -void kernel_dgetrf_nn_r_12x4_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dgetrf_nn_r_12x4_vs_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -void kernel_dgetrf_nt_l_12x4_lib4(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dgetrf_nt_l_12x4_vs_lib4(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -void kernel_dgetrf_nt_m_12x4_lib4(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dgetrf_nt_m_12x4_vs_lib4(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -void kernel_dgetrf_nt_r_12x4_lib4(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dgetrf_nt_r_12x4_vs_lib4(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -// 8x8 -void kernel_dpotrf_nt_l_8x8_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dpotrf_nt_l_8x8_vs_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -// 8x4 -void kernel_dpotrf_nt_l_8x4_lib4(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dpotrf_nt_l_8x4_vs_lib4(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -void kernel_dgetrf_nn_l_8x4_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dgetrf_nn_l_8x4_vs_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -void kernel_dgetrf_nn_r_8x4_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dgetrf_nn_r_8x4_vs_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -void kernel_dgetrf_nt_l_8x4_lib4(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dgetrf_nt_l_8x4_vs_lib4(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -void kernel_dgetrf_nt_r_8x4_lib4(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dgetrf_nt_r_8x4_vs_lib4(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -// 4x4 -void kernel_dpotrf_nt_l_4x4_lib4(int k, double *A, double *B, double *C, double *D, double *inv_diag_D); -void kernel_dpotrf_nt_l_4x4_vs_lib4(int k, double *A, double *B, double *C, double *D, double *inv_diag_D, int km, int kn); -#if defined(TARGET_X64_INTEL_SANDY_BRIDGE) -void kernel_dlauum_nt_4x4_lib4(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D); // -void kernel_dlauum_nt_4x4_vs_lib4(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D, int km, int kn); // -#endif -void kernel_dgetrf_nn_4x4_lib4(int k, double *A, double *B, int sdb, double *C, double *D, double *inv_diag_D); -void kernel_dgetrf_nn_4x4_vs_lib4(int k, double *A, double *B, int sdb, double *C, double *D, double *inv_diag_D, int km, int kn); -void kernel_dgetrf_nt_4x4_lib4(int k, double *A, double *B, double *C, double *D, double *inv_diag_D); -void kernel_dgetrf_nt_4x4_vs_lib4(int k, double *A, double *B, double *C, double *D, double *inv_diag_D, int km, int kn); -void kernel_dgeqrf_4_lib4(int m, double *pD, int sdd, double *dD); -void kernel_dgeqrf_vs_lib4(int m, int n, int k, int offD, double *pD, int sdd, double *dD); -void kernel_dlarf_4_lib4(int m, int n, double *pV, int sdv, double *tau, double *pC, int sdc); // rank-4 reflector -void kernel_dlarf_t_4_lib4(int m, int n, double *pD, int sdd, double *pVt, double *dD, double *pC0, int sdc, double *pW); -void kernel_dgelqf_4_lib4(int n, double *pD, double *dD); -void kernel_dgelqf_vs_lib4(int m, int n, int k, int offD, double *pD, int sdd, double *dD); -void kernel_dlarft_4_lib4(int kmax, double *pD, double *dD, double *pT); -void kernel_dlarft_3_lib4(int kmax, double *pD, double *dD, double *pT); -void kernel_dlarft_2_lib4(int kmax, double *pD, double *dD, double *pT); -void kernel_dlarft_1_lib4(int kmax, double *pD, double *dD, double *pT); -void kernel_dgelqf_dlarft12_12_lib4(int n, double *pD, int sdd, double *dD, double *pT); -void kernel_dgelqf_dlarft4_12_lib4(int n, double *pD, int sdd, double *dD, double *pT); -void kernel_dgelqf_dlarft4_8_lib4(int n, double *pD, int sdd, double *dD, double *pT); -void kernel_dgelqf_dlarft4_4_lib4(int n, double *pD, double *dD, double *pT); -void kernel_dlarfb12_rn_12_lib4(int kmax, double *pV, int sdd, double *pT, double *pD, double *pK); -void kernel_dlarfb12_rn_4_lib4(int kmax, double *pV, int sdd, double *pT, double *pD, double *pK, int km); -void kernel_dlarfb4_rn_12_lib4(int kmax, double *pV, double *pT, double *pD, int sdd); -void kernel_dlarfb4_rn_8_lib4(int kmax, double *pV, double *pT, double *pD, int sdd); -void kernel_dlarfb4_rn_4_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb3_rn_4_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb2_rn_4_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb1_rn_4_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb4_rn_1_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb3_rn_1_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb2_rn_1_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb1_rn_1_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb4_rt_4_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb3_rt_4_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb2_rt_4_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb1_rt_4_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb4_rt_1_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb3_rt_1_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb2_rt_1_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb1_rt_1_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dgelqf_pd_dlarft12_12_lib4(int n, double *pD, int sdd, double *dD, double *pT); -void kernel_dgelqf_pd_dlarft4_8_lib4(int n, double *pD, int sdd, double *dD, double *pT); -void kernel_dgelqf_pd_dlarft4_4_lib4(int n, double *pD, double *dD, double *pT); -void kernel_dgelqf_pd_4_lib4(int n, double *pD, double *dD); -void kernel_dgelqf_pd_vs_lib4(int m, int n, int k, int offD, double *pD, int sdd, double *dD); -void kernel_dgelqf_pd_la_vs_lib4(int m, int n1, int k, int offD, double *pD, int sdd, double *dD, int offA, double *pA, int sda); -void kernel_dlarft_4_la_lib4(int n1, double *dD, double *pA, double *pT); -void kernel_dlarfb4_rn_12_la_lib4(int n1, double *pVA, double *pT, double *pD, int sdd, double *pA, int sda); -void kernel_dlarfb4_rn_8_la_lib4(int n1, double *pVA, double *pT, double *pD, int sdd, double *pA, int sda); -void kernel_dlarfb4_rn_4_la_lib4(int n1, double *pVA, double *pT, double *pD, double *pA); -void kernel_dlarfb4_rn_1_la_lib4(int n1, double *pVA, double *pT, double *pD, double *pA); -void kernel_dgelqf_pd_lla_vs_lib4(int m, int n0, int n1, int k, int offD, double *pD, int sdd, double *dD, int offL, double *pL, int sdl, int offA, double *pA, int sda); -void kernel_dlarft_4_lla_lib4(int n0, int n1, double *dD, double *pL, double *pA, double *pT); -void kernel_dlarfb4_rn_12_lla_lib4(int n0, int n1, double *pVL, double *pVA, double *pT, double *pD, int sdd, double *pL, int sdl, double *pA, int sda); -void kernel_dlarfb4_rn_8_lla_lib4(int n0, int n1, double *pVL, double *pVA, double *pT, double *pD, int sdd, double *pL, int sdl, double *pA, int sda); -void kernel_dlarfb4_rn_4_lla_lib4(int n0, int n1, double *pVL, double *pVA, double *pT, double *pD, double *pL, double *pA); -void kernel_dlarfb4_rn_1_lla_lib4(int n0, int n1, double *pVL, double *pVA, double *pT, double *pD, double *pL, double *pA); -// 4x2 -void kernel_dpotrf_nt_l_4x2_lib4(int k, double *A, double *B, double *C, double *D, double *inv_diag_D); -void kernel_dpotrf_nt_l_4x2_vs_lib4(int k, double *A, double *B, double *C, double *D, double *inv_diag_D, int km, int kn); -// 2x2 -void kernel_dpotrf_nt_l_2x2_lib4(int k, double *A, double *B, double *C, double *D, double *inv_diag_D); -void kernel_dpotrf_nt_l_2x2_vs_lib4(int k, double *A, double *B, double *C, double *D, double *inv_diag_D, int km, int kn); -// 12 -void kernel_dgetrf_pivot_12_lib4(int m, double *pA, int sda, double *inv_diag_A, int* ipiv); -void kernel_dgetrf_pivot_12_vs_lib4(int m, double *pA, int sda, double *inv_diag_A, int* ipiv, int n); -// 8 -void kernel_dgetrf_pivot_8_lib4(int m, double *pA, int sda, double *inv_diag_A, int* ipiv); -void kernel_dgetrf_pivot_8_vs_lib4(int m, double *pA, int sda, double *inv_diag_A, int* ipiv, int n); -// 4 -void kernel_dgetrf_pivot_4_lib4(int m, double *pA, int sda, double *inv_diag_A, int* ipiv); -void kernel_dgetrf_pivot_4_vs_lib4(int m, double *pA, int sda, double *inv_diag_A, int* ipiv, int n1); -// vector -void kernel_drowsw_lib4(int kmax, double *pA, double *pC); - - - -// merged routines -// 12x4 -void kernel_dgemm_dtrsm_nt_rl_inv_12x4_lib4(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E); -void kernel_dgemm_dtrsm_nt_rl_inv_12x4_vs_lib4(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E, int km, int kn); -void kernel_dsyrk_dpotrf_nt_l_12x4_lib4(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dsyrk_dpotrf_nt_l_12x4_vs_lib4(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -// 4x12 -void kernel_dgemm_dtrsm_nt_rl_inv_4x12_vs_lib4(int kp, double *Ap, double *Bp, int sdbp, int km_, double *Am, double *Bm, int sdbm, double *C, double *D, double *E, int sde, double *inv_diag_E, int km, int kn); -// 8x8 -void kernel_dsyrk_dpotrf_nt_l_8x8_lib4(int kp, double *Ap, int sdap, double *Bp, int sdbp, int km_, double *Am, int sdam, double *Bm, int sdbm, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dsyrk_dpotrf_nt_l_8x8_vs_lib4(int kp, double *Ap, int sdap, double *Bp, int sdbp, int km_, double *Am, int sdam, double *Bm, int sdbm, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -void kernel_dgemm_dtrsm_nt_rl_inv_8x8l_vs_lib4(int kp, double *Ap, int sdap, double *Bp, int sdb, int km_, double *Am, int sdam, double *Bm, int sdbm, double *C, int sdc, double *D, int sdd, double *E, int sde, double *inv_diag_E, int km, int kn); -void kernel_dgemm_dtrsm_nt_rl_inv_8x8u_vs_lib4(int kp, double *Ap, int sdap, double *Bp, int sdb, int km_, double *Am, int sdam, double *Bm, int sdbm, double *C, int sdc, double *D, int sdd, double *E, int sde, double *inv_diag_E, int km, int kn); -// 8x4 -void kernel_dgemm_dtrsm_nt_rl_inv_8x4_lib4(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E); -void kernel_dgemm_dtrsm_nt_rl_inv_8x4_vs_lib4(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E, int km, int kn); -void kernel_dsyrk_dpotrf_nt_l_8x4_lib4(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dsyrk_dpotrf_nt_l_8x4_vs_lib4(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -// 4x8 -void kernel_dgemm_dtrsm_nt_rl_inv_4x8_vs_lib4(int kp, double *Ap, double *Bp, int sdbp, int km_, double *Am, double *Bm, int sdbm, double *C, double *D, double *E, int sde, double *inv_diag_E, int km, int kn); -// 4x4 -void kernel_dgemm_dtrsm_nt_rl_inv_4x4_lib4(int kp, double *Ap, double *Bp, int km_, double *Am, double *Bm, double *C, double *D, double *E, double *inv_diag_E); -void kernel_dgemm_dtrsm_nt_rl_inv_4x4_vs_lib4(int kp, double *Ap, double *Bp, int km_, double *Am, double *Bm, double *C, double *D, double *E, double *inv_diag_E, int km, int kn); -void kernel_dsyrk_dpotrf_nt_l_4x4_lib4(int kp, double *Ap, double *Bp, int km_, double *Am, double *Bm, double *C, double *D, double *inv_diag_D); -void kernel_dsyrk_dpotrf_nt_l_4x4_vs_lib4(int kp, double *Ap, double *Bp, int km_, double *Am, double *Bm, double *C, double *D, double *inv_diag_D, int km, int kn); -// 4x2 -void kernel_dgemm_dtrsm_nt_rl_inv_4x2_lib4(int kp, double *Ap, double *Bp, int km_, double *Am, double *Bm, double *C, double *D, double *E, double *inv_diag_E); -void kernel_dgemm_dtrsm_nt_rl_inv_4x2_vs_lib4(int kp, double *Ap, double *Bp, int km_, double *Am, double *Bm, double *C, double *D, double *E, double *inv_diag_E, int km, int kn); -void kernel_dsyrk_dpotrf_nt_l_4x2_lib4(int kp, double *Ap, double *Bp, int km_, double *Am, double *Bm, double *C, double *D, double *inv_diag_D); -void kernel_dsyrk_dpotrf_nt_l_4x2_vs_lib4(int kp, double *Ap, double *Bp, int km_, double *Am, double *Bm, double *C, double *D, double *inv_diag_D, int km, int kn); -// 2x2 -void kernel_dsyrk_dpotrf_nt_l_2x2_lib4(int kp, double *Ap, double *Bp, int km_, double *Am, double *Bm, double *C, double *D, double *inv_diag_D); -void kernel_dsyrk_dpotrf_nt_l_2x2_vs_lib4(int kp, double *Ap, double *Bp, int km_, double *Am, double *Bm, double *C, double *D, double *inv_diag_D, int km, int kn); - -/* - * - * Auxiliary routines - * - * cpsc copy and scale, scale - * cp copy - * add - * set and scale - * transpose and scale - * set and scale - * - */ - -// copy and scale -void kernel_dgecpsc_8_0_lib4(int tri, int kmax, double alpha, double *A0, int sda, double *B, int sdb); -void kernel_dgecpsc_8_1_lib4(int tri, int kmax, double alpha, double *A0, int sda, double *B, int sdb); -void kernel_dgecpsc_8_2_lib4(int tri, int kmax, double alpha, double *A0, int sda, double *B, int sdb); -void kernel_dgecpsc_8_3_lib4(int tri, int kmax, double alpha, double *A0, int sda, double *B, int sdb); - -void kernel_dgecpsc_4_0_lib4(int tri, int kmax, double alpha, double *A, double *B); -void kernel_dgecpsc_4_1_lib4(int tri, int kmax, double alpha, double *A0, int sda, double *B); -void kernel_dgecpsc_4_2_lib4(int tri, int kmax, double alpha, double *A0, int sda, double *B); -void kernel_dgecpsc_4_3_lib4(int tri, int kmax, double alpha, double *A0, int sda, double *B); - -void kernel_dgecpsc_3_0_lib4(int tri, int kmax, double alpha, double *A, double *B); -void kernel_dgecpsc_3_2_lib4(int tri, int kmax, double alpha, double *A0, int sda, double *B); -void kernel_dgecpsc_3_3_lib4(int tri, int kmax, double alpha, double *A0, int sda, double *B); - -void kernel_dgecpsc_2_0_lib4(int tri, int kmax, double alpha, double *A, double *B); -void kernel_dgecpsc_2_3_lib4(int tri, int kmax, double alpha, double *A0, int sda, double *B); - -void kernel_dgecpsc_1_0_lib4(int tri, int kmax, double alpha, double *A, double *B); - -// copy only -void kernel_dgecp_8_0_lib4(int tri, int kmax, double *A, int sda, double *B, int sdb); - -void kernel_dgecp_4_0_lib4(int tri, int kmax, double *A, double *B); - -// add -void kernel_dgead_8_0_lib4(int kmax, double alpha, double *A0, int sda, double *B, int sdb); -void kernel_dgead_8_1_lib4(int kmax, double alpha, double *A0, int sda, double *B, int sdb); -void kernel_dgead_8_2_lib4(int kmax, double alpha, double *A0, int sda, double *B, int sdb); -void kernel_dgead_8_3_lib4(int kmax, double alpha, double *A0, int sda, double *B, int sdb); -void kernel_dgead_4_0_lib4(int kmax, double alpha, double *A, double *B); -void kernel_dgead_4_1_lib4(int kmax, double alpha, double *A0, int sda, double *B); -void kernel_dgead_4_2_lib4(int kmax, double alpha, double *A0, int sda, double *B); -void kernel_dgead_4_3_lib4(int kmax, double alpha, double *A0, int sda, double *B); -void kernel_dgead_3_0_lib4(int kmax, double alpha, double *A, double *B); -void kernel_dgead_3_2_lib4(int kmax, double alpha, double *A0, int sda, double *B); -void kernel_dgead_3_3_lib4(int kmax, double alpha, double *A0, int sda, double *B); -void kernel_dgead_2_0_lib4(int kmax, double alpha, double *A, double *B); -void kernel_dgead_2_3_lib4(int kmax, double alpha, double *A0, int sda, double *B); -void kernel_dgead_1_0_lib4(int kmax, double alpha, double *A, double *B); - -// set -void kernel_dgeset_4_lib4(int kmax, double alpha, double *A); -void kernel_dtrset_4_lib4(int kmax, double alpha, double *A); - -// traspose -void kernel_dgetr_8_lib4(int tri, int kmax, int kna, double alpha, double *A, int sda, double *C, int sdc); -void kernel_dgetr_4_lib4(int tri, int kmax, int kna, double alpha, double *A, double *C, int sdc); -void kernel_dgetr_3_lib4(int tri, int kmax, int kna, double alpha, double *A, double *C, int sdc); -void kernel_dgetr_2_lib4(int tri, int kmax, int kna, double alpha, double *A, double *C, int sdc); -void kernel_dgetr_1_lib4(int tri, int kmax, int kna, double alpha, double *A, double *C, int sdc); -void kernel_dgetr_4_0_lib4(int m, double *A, int sda, double *B); - - - -// pack -// 12 -void kernel_dpack_nn_12_lib4(int kmax, double *A, int lda, double *B, int sdb); -void kernel_dpack_nn_12_vs_lib4(int kmax, double *A, int lda, double *B, int sdb, int m1); -void kernel_dpack_tt_12_lib4(int kmax, double *A, int lda, double *B, int sdb); -// 8 -void kernel_dpack_nn_8_lib4(int kmax, double *A, int lda, double *B, int sdb); -void kernel_dpack_nn_8_vs_lib4(int kmax, double *A, int lda, double *B, int sdb, int m1); -void kernel_dpack_tt_8_lib4(int kmax, double *A, int lda, double *B, int sdb); -// 4 -void kernel_dpack_nn_4_lib4(int kmax, double *A, int lda, double *B); -void kernel_dpack_nn_4_vs_lib4(int kmax, double *A, int lda, double *B, int m1); -void kernel_dpack_tn_4_p0_lib4(int kmax, double *A, int lda, double *B); -void kernel_dpack_tn_4_lib4(int kmax, double *A, int lda, double *B); -void kernel_dpack_tn_4_vs_lib4(int kmax, double *A, int lda, double *B, int m1); -void kernel_dpack_tt_4_lib4(int kmax, double *A, int lda, double *B, int sdb); -void kernel_dpack_tt_4_vs_lib4(int kmax, double *A, int lda, double *B, int sdb, int m1); -// unpack -// 12 -void kernel_dunpack_nn_12_lib4(int kmax, double *A, int sda, double *B, int ldb); -void kernel_dunpack_nn_12_vs_lib4(int kmax, double *A, int sda, double *B, int ldb, int m1); -void kernel_dunpack_tt_12_lib4(int kmax, double *A, int sda, double *B, int ldb); -// 8 -void kernel_dunpack_nn_8_lib4(int kmax, double *A, int sda, double *B, int ldb); -void kernel_dunpack_nn_8_vs_lib4(int kmax, double *A, int sda, double *B, int ldb, int m1); -void kernel_dunpack_tt_8_lib4(int kmax, double *A, int sda, double *B, int ldb); -// 4 -void kernel_dunpack_nn_4_lib4(int kmax, double *A, double *B, int ldb); -void kernel_dunpack_nn_4_vs_lib4(int kmax, double *A, double *B, int ldb, int m1); -void kernel_dunpack_nt_4_lib4(int kmax, double *A, double *B, int ldb); -void kernel_dunpack_nt_4_vs_lib4(int kmax, double *A, double *B, int ldb, int m1); -void kernel_dunpack_tt_4_lib4(int kmax, double *A, int sda, double *B, int ldb); - -// panel copy -// 12 -void kernel_dpacp_nn_12_lib4(int kmax, int offsetA, double *A, int sda, double *B, int sdb); -void kernel_dpacp_nn_12_vs_lib4(int kmax, int offsetA, double *A, int sda, double *B, int sdb, int m1); -// 8 -void kernel_dpacp_nn_8_lib4(int kmax, int offsetA, double *A, int sda, double *B, int sdb); -void kernel_dpacp_nn_8_vs_lib4(int kmax, int offsetA, double *A, int sda, double *B, int sdb, int m1); -// 4 -void kernel_dpacp_nt_4_lib4(int kmax, double *A, int offsetB, double *B, int sdb); -void kernel_dpacp_tn_4_lib4(int kmax, int offsetA, double *A, int sda, double *B); -void kernel_dpacp_nn_4_lib4(int kmax, int offsetA, double *A, int sda, double *B); -void kernel_dpacp_nn_4_vs_lib4(int kmax, int offsetA, double *A, int sda, double *B, int m1); - - - -/************************************************ -* BLAS API kernels -************************************************/ - -//#if defined(BLAS_API) - -// A, B panel-major bs=4; C, D column-major -// 12x4 -void kernel_dgemm_nt_12x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_12x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nt_12x4_p0_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *A_p, double *B_p); -void kernel_dsyrk_nt_l_12x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyrk_nt_l_12x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dsyrk_nt_u_12x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyrk_nt_u_12x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dger2k_nt_12x4_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, double *A1, int sda1, double *B1, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dger2k_nt_12x4_vs_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, double *A1, int sda1, double *B1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dsyr2k_nt_l_12x4_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, double *A1, int sda1, double *B1, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyr2k_nt_l_12x4_vs_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, double *A1, int sda1, double *B1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_12x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_rl_12x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_one_12x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_rl_one_12x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_12x4_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_ru_12x4_vs_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_12x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_ru_12x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_one_12x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_ru_one_12x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrsm_nt_ll_inv_12x4_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int sde, double *inv_diag_E); -void kernel_dtrsm_nt_ll_inv_12x4_vs_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int sde, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nt_rl_inv_12x4_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE); -void kernel_dtrsm_nt_rl_inv_12x4_vs_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE, int m1, int n1); -void kernel_dtrsm_nt_rl_inv_12x4_lib44ccc(int kmax, double *A, int sda, double *B, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nt_rl_inv_12x4_vs_lib44ccc(int kmax, double *A, int sda, double *B, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_rl_one_12x4_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E); -void kernel_dtrsm_nt_rl_one_12x4_vs_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int m1, int n1); -void kernel_dtrsm_nt_ru_inv_12x4_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE); -void kernel_dtrsm_nt_ru_inv_12x4_vs_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE, int m1, int n1); -void kernel_dtrsm_nt_ru_one_12x4_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E); -void kernel_dtrsm_nt_ru_one_12x4_vs_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int m1, int n1); -void kernel_dpotrf_nt_l_12x4_lib44cc(int kmax, double *A, int sda, double *B, double *C, int ldc, double *D, int ldd, double *dD); -void kernel_dpotrf_nt_l_12x4_vs_lib44cc(int kmax, double *A, int sda, double *B, double *C, int ldc, double *D, int ldd, double *dD, int m1, int n1); -// 4x12 -void kernel_dgemm_nt_4x12_lib44cc(int kmax, double *alpha, double *A, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_4x12_vs_lib44cc(int kmax, double *alpha, double *A, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nt_4x12_p0_vs_lib44cc(int kmax, double *alpha, double *A, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1, double *A_p, double *B_p); -void kernel_dtrmm_nt_rl_4x12_tran_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_rl_4x12_tran_vs_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_one_4x12_tran_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_rl_one_4x12_tran_vs_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_4x12_tran_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_ru_4x12_tran_vs_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_one_4x12_tran_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_ru_one_4x12_tran_vs_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -// 8x8 -void kernel_dsyrk_nt_l_8x8_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyrk_nt_l_8x8_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dsyrk_nt_u_8x8_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyrk_nt_u_8x8_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dger2k_nt_8x8_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, int sdb0, double *A1, int sda1, double *B1, int sdb1, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dger2k_nt_8x8_vs_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, int sdb0, double *A1, int sda1, double *B1, int sdb1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dsyr2k_nt_l_8x8_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, int sdb0, double *A1, int sda1, double *B1, int sdb1, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyr2k_nt_l_8x8_vs_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, int sdb0, double *A1, int sda1, double *B1, int sdb1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dpotrf_nt_l_8x8_lib44cc(int kmax, double *A, int sda, double *B, int sdb, double *C, int ldc, double *D, int ldd, double *dD); -void kernel_dpotrf_nt_l_8x8_vs_lib44cc(int kmax, double *A, int sda, double *B, int sdb, double *C, int ldc, double *D, int ldd, double *dD, int m1, int n1); -// 8x4 -void kernel_dgemm_nt_8x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_8x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nt_8x4_p0_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *A_p, double *B_p); -void kernel_dgemm_nt_8x4_p_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *A_p); -void kernel_dsyrk_nt_l_8x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyrk_nt_l_8x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dsyrk_nt_u_8x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyrk_nt_u_8x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dger2k_nt_8x4_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, double *A1, int sda1, double *B1, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dger2k_nt_8x4_vs_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, double *A1, int sda1, double *B1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dsyr2k_nt_l_8x4_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, double *A1, int sda1, double *B1, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyr2k_nt_l_8x4_vs_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, double *A1, int sda1, double *B1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_8x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_rl_8x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_one_8x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_rl_one_8x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_8x4_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_ru_8x4_vs_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_8x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_ru_8x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_one_8x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_ru_one_8x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrsm_nt_ll_inv_8x4_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int sde, double *inv_diag_E); -void kernel_dtrsm_nt_ll_inv_8x4_vs_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int sde, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nt_rl_inv_8x4_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE); -void kernel_dtrsm_nt_rl_inv_8x4_vs_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE, int m1, int n1); -void kernel_dtrsm_nt_rl_inv_8x4_lib44ccc(int kmax, double *A, int sda, double *B, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nt_rl_inv_8x4_vs_lib44ccc(int kmax, double *A, int sda, double *B, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_rl_one_8x4_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E); -void kernel_dtrsm_nt_rl_one_8x4_vs_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int m1, int n1); -void kernel_dtrsm_nt_ru_inv_8x4_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE); -void kernel_dtrsm_nt_ru_inv_8x4_vs_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE, int m1, int n1); -void kernel_dtrsm_nt_ru_one_8x4_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E); -void kernel_dtrsm_nt_ru_one_8x4_vs_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int m1, int n1); -void kernel_dpotrf_nt_l_8x4_lib44cc(int kmax, double *A, int sda, double *B, double *C, int ldc, double *D, int ldd, double *dD); -void kernel_dpotrf_nt_l_8x4_vs_lib44cc(int kmax, double *A, int sda, double *B, double *C, int ldc, double *D, int ldd, double *dD, int m1, int n1); -// 4x8 -void kernel_dgemm_nt_4x8_lib44cc(int kmax, double *alpha, double *A, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_4x8_vs_lib44cc(int kmax, double *alpha, double *A, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_4x8_tran_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_rl_4x8_tran_vs_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_one_4x8_tran_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_rl_one_4x8_tran_vs_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_4x8_tran_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_ru_4x8_tran_vs_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_one_4x8_tran_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_ru_one_4x8_tran_vs_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -// 4x4 -void kernel_dgemm_nt_4x4_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_4x4_vs_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dsyrk_nt_l_4x4_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyrk_nt_l_4x4_vs_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dsyrk_nt_u_4x4_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyrk_nt_u_4x4_vs_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dger2k_nt_4x4_lib44cc(int kmax, double *alpha, double *A0, double *B0, double *A1, double *B1, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dger2k_nt_4x4_vs_lib44cc(int kmax, double *alpha, double *A0, double *B0, double *A1, double *B1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dsyr2k_nt_l_4x4_lib44cc(int kmax, double *alpha, double *A0, double *B0, double *A1, double *B1, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyr2k_nt_l_4x4_vs_lib44cc(int kmax, double *alpha, double *A0, double *B0, double *A1, double *B1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_4x4_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_rl_4x4_vs_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_4x4_tran_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd); -void kernel_dtrmm_nt_rl_4x4_tran_vs_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_one_4x4_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_rl_one_4x4_vs_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_one_4x4_tran_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd); -void kernel_dtrmm_nt_rl_one_4x4_tran_vs_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_4x4_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd); -void kernel_dtrmm_nt_ru_4x4_vs_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_4x4_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_ru_4x4_vs_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_4x4_tran_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd); -void kernel_dtrmm_nt_ru_4x4_tran_vs_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_one_4x4_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_ru_one_4x4_vs_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_one_4x4_tran_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd); -void kernel_dtrmm_nt_ru_one_4x4_tran_vs_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd, int m1, int n1); -void kernel_dtrsm_nt_ll_inv_4x4_lib44cc4(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *inv_diag_E); -void kernel_dtrsm_nt_ll_inv_4x4_vs_lib44cc4(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nt_rl_inv_4x4_lib44cc4(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE); -void kernel_dtrsm_nt_rl_inv_4x4_vs_lib44cc4(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE, int m1, int n1); -void kernel_dtrsm_nt_rl_inv_4x4_lib44ccc(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nt_rl_inv_4x4_vs_lib44ccc(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_rl_one_4x4_lib44cc4(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E); -void kernel_dtrsm_nt_rl_one_4x4_vs_lib44cc4(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int m1, int n1); -void kernel_dtrsm_nt_ru_inv_4x4_lib44cc4(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE); -void kernel_dtrsm_nt_ru_inv_4x4_vs_lib44cc4(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE, int m1, int n1); -void kernel_dtrsm_nt_ru_one_4x4_lib44cc4(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E); -void kernel_dtrsm_nt_ru_one_4x4_vs_lib44cc4(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int m1, int n1); -void kernel_dpotrf_nt_l_4x4_lib44cc(int kmax, double *A, double *B, double *C, int ldc, double *D, int ldd, double *dD); -void kernel_dpotrf_nt_l_4x4_vs_lib44cc(int kmax, double *A, double *B, double *C, int ldc, double *D, int ldd, double *dD, int m1, int n1); -// 4x2 -void kernel_dgemm_nt_4x2_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd); - -// A panel-major bs=4; B, C, D column-major -// 12x4 -void kernel_dgemm_nn_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nn_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nt_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dsyrk_nt_l_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyrk_nt_l_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dger2k_nt_12x4_lib4ccc(int kmax, double *alpha, double *A0, int sda0, double *B0, int ldb0, double *A1, int sda1, double *B1, int ldb1, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dger2k_nt_12x4_vs_lib4ccc(int kmax, double *alpha, double *A0, int sda0, double *B0, int ldb0, double *A1, int sda1, double *B1, int ldb1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_rl_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nn_rl_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_rl_one_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nn_rl_one_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_ru_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nn_ru_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_ru_one_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nn_ru_one_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_rl_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_one_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_rl_one_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_ru_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_one_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_ru_one_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrsm_nn_ll_inv_12x4_lib4ccc4(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int sde, double *inv_diag_E); -void kernel_dtrsm_nn_ll_inv_12x4_vs_lib4ccc4(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int sde, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nn_ll_one_12x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nn_ll_one_12x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nn_rl_inv_12x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nn_rl_inv_12x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nn_rl_one_12x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nn_rl_one_12x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nt_rl_inv_12x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nt_rl_inv_12x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_rl_one_12x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nt_rl_one_12x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nn_ru_inv_12x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nn_ru_inv_12x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nn_ru_one_12x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nn_ru_one_12x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nt_ru_inv_12x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nt_ru_inv_12x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_ru_one_12x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nt_ru_one_12x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dgetrf_nn_l_12x4_lib4ccc(int kmax, double *A, int sda, double *B, int ldb, double *C, int ldc, double *D, int ldd, double *diag); -void kernel_dgetrf_nn_l_12x4_vs_lib4ccc(int kmax, double *A, int sda, double *B, int ldb, double *C, int ldc, double *D, int ldd, double *diag, int m1, int n1); -void kernel_dgetrf_nn_m_12x4_lib4ccc(int kmax, double *A, int sda, double *B, int ldb, double *C, int ldc, double *D, int ldd, double *diag); -void kernel_dgetrf_nn_m_12x4_vs_lib4ccc(int kmax, double *A, int sda, double *B, int ldb, double *C, int ldc, double *D, int ldd, double *diag, int m1, int n1); -void kernel_dgetrf_nn_r_12x4_lib4ccc(int kmax, double *A, int sda, double *B, int ldb, double *C, int ldc, double *D, int ldd, double *diag); -void kernel_dgetrf_nn_r_12x4_vs_lib4ccc(int kmax, double *A, int sda, double *B, int ldb, double *C, int ldc, double *D, int ldd, double *diag, int m1, int n1); -// 4x12 -void kernel_dgemm_nn_4x12_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nn_4x12_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nt_4x12_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_4x12_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_rl_4x12_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nn_rl_4x12_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_rl_one_4x12_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nn_rl_one_4x12_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_ru_4x12_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nn_ru_4x12_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_ru_one_4x12_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nn_ru_one_4x12_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_4x12_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_rl_4x12_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_one_4x12_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_rl_one_4x12_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_4x12_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_ru_4x12_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_one_4x12_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_ru_one_4x12_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -// 8x4 -void kernel_dgemm_nn_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nn_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nt_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dsyrk_nt_l_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyrk_nt_l_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dger2k_nt_8x4_lib4ccc(int kmax, double *alpha, double *A0, int sda0, double *B0, int ldb0, double *A1, int sda1, double *B1, int ldb1, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dger2k_nt_8x4_vs_lib4ccc(int kmax, double *alpha, double *A0, int sda0, double *B0, int ldb0, double *A1, int sda1, double *B1, int ldb1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_rl_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nn_rl_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_rl_one_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nn_rl_one_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_ru_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nn_ru_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_ru_one_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nn_ru_one_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_rl_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_one_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_rl_one_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_ru_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_one_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_ru_one_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrsm_nn_ll_inv_8x4_lib4ccc4(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int sde, double *inv_diag_E); -void kernel_dtrsm_nn_ll_inv_8x4_vs_lib4ccc4(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int sde, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nn_ll_one_8x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nn_ll_one_8x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nn_rl_inv_8x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nn_rl_inv_8x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nn_rl_one_8x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nn_rl_one_8x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nt_rl_inv_8x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nt_rl_inv_8x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_rl_one_8x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nt_rl_one_8x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nn_ru_inv_8x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nn_ru_inv_8x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nn_ru_one_8x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nn_ru_one_8x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nt_ru_inv_8x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nt_ru_inv_8x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_ru_one_8x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nt_ru_one_8x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dgetrf_nn_l_8x4_lib4ccc(int kmax, double *A, int sda, double *B, int ldb, double *C, int ldc, double *D, int ldd, double *diag); -void kernel_dgetrf_nn_l_8x4_vs_lib4ccc(int kmax, double *A, int sda, double *B, int ldb, double *C, int ldc, double *D, int ldd, double *diag, int m1, int n1); -void kernel_dgetrf_nn_r_8x4_lib4ccc(int kmax, double *A, int sda, double *B, int ldb, double *C, int ldc, double *D, int ldd, double *diag); -void kernel_dgetrf_nn_r_8x4_vs_lib4ccc(int kmax, double *A, int sda, double *B, int ldb, double *C, int ldc, double *D, int ldd, double *diag, int m1, int n1); -// 4x8 -void kernel_dgemm_nn_4x8_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nn_4x8_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nt_4x8_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_4x8_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_rl_4x8_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nn_rl_4x8_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_rl_one_4x8_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nn_rl_one_4x8_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_ru_4x8_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nn_ru_4x8_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_ru_one_4x8_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nn_ru_one_4x8_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_4x8_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_rl_4x8_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_one_4x8_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_rl_one_4x8_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_4x8_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_ru_4x8_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_one_4x8_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_ru_one_4x8_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -// 4x4 -void kernel_dgemm_nn_4x4_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nn_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nt_4x4_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dsyrk_nt_l_4x4_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyrk_nt_l_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dger2k_nt_4x4_lib4ccc(int kmax, double *alpha, double *A0, double *B0, int ldb0, double *A1, double *B1, int ldb1, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dger2k_nt_4x4_vs_lib4ccc(int kmax, double *alpha, double *A0, double *B0, int ldb0, double *A1, double *B1, int ldb1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_rl_4x4_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nn_rl_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_rl_4x4_tran_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd); -void kernel_dtrmm_nn_rl_4x4_tran_vs_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_rl_one_4x4_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nn_rl_one_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_rl_one_4x4_tran_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd); -void kernel_dtrmm_nn_rl_one_4x4_tran_vs_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_ru_4x4_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nn_ru_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_ru_4x4_tran_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd); -void kernel_dtrmm_nn_ru_4x4_tran_vs_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_ru_one_4x4_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nn_ru_one_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_ru_one_4x4_tran_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd); -void kernel_dtrmm_nn_ru_one_4x4_tran_vs_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_4x4_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_rl_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_4x4_tran_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd); -void kernel_dtrmm_nt_rl_4x4_tran_vs_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_one_4x4_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_rl_one_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_one_4x4_tran_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd); -void kernel_dtrmm_nt_rl_one_4x4_tran_vs_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_4x4_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_ru_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_4x4_tran_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd); -void kernel_dtrmm_nt_ru_4x4_tran_vs_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_one_4x4_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_ru_one_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_one_4x4_tran_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd); -void kernel_dtrmm_nt_ru_one_4x4_tran_vs_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd, int m1, int n1); -void kernel_dtrsm_nn_ll_inv_4x4_lib4ccc4(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *inv_diag_E); -void kernel_dtrsm_nn_ll_inv_4x4_vs_lib4ccc4(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nn_ll_one_4x4_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nn_ll_one_4x4_vs_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nn_rl_inv_4x4_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nn_rl_inv_4x4_vs_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nn_rl_one_4x4_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nn_rl_one_4x4_vs_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nt_rl_inv_4x4_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nt_rl_inv_4x4_vs_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_rl_one_4x4_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nt_rl_one_4x4_vs_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nn_ru_inv_4x4_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nn_ru_inv_4x4_vs_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nn_ru_one_4x4_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nn_ru_one_4x4_vs_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nt_ru_inv_4x4_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nt_ru_inv_4x4_vs_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_ru_one_4x4_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nt_ru_one_4x4_vs_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dgetrf_nn_4x4_lib4ccc(int kmax, double *A, double *B, int ldb, double *C, int ldc, double *D, int ldd, double *diag); -void kernel_dgetrf_nn_4x4_vs_lib4ccc(int kmax, double *A, double *B, int ldb, double *C, int ldc, double *D, int ldd, double *diag, int m1, int n1); - -// B panel-major bs=4; A, C, D column-major -// 12x4 -void kernel_dgemm_nt_12x4_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_12x4_vs_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_tt_12x4_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_tt_12x4_vs_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -// 4x12 -void kernel_dgemm_nt_4x12_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_4x12_vs_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_tt_4x12_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_tt_4x12_vs_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -// 8x4 -void kernel_dgemm_nt_8x4_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_8x4_vs_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_tt_8x4_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_tt_8x4_vs_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -// 4x8 -void kernel_dgemm_nt_4x8_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_4x8_vs_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_tt_4x8_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_tt_4x8_vs_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -// 4x4 -void kernel_dgemm_nt_4x4_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_4x4_vs_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_tt_4x4_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_tt_4x4_vs_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); - -// A, C, D panel-major; B, E column-major -// TODO merge with above -// 12x4 -void kernel_dtrsm_nn_rl_inv_12x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE); -void kernel_dtrsm_nn_rl_inv_12x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nn_rl_one_12x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde); -void kernel_dtrsm_nn_rl_one_12x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nn_ru_inv_12x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE); -void kernel_dtrsm_nn_ru_inv_12x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nn_ru_one_12x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde); -void kernel_dtrsm_nn_ru_one_12x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nt_rl_inv_12x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE); -void kernel_dtrsm_nt_rl_inv_12x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_rl_one_12x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde); -void kernel_dtrsm_nt_rl_one_12x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nt_ru_inv_12x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE); -void kernel_dtrsm_nt_ru_inv_12x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_ru_one_12x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde); -void kernel_dtrsm_nt_ru_one_12x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, int m1, int n1); -// 8x4 -void kernel_dtrsm_nn_rl_inv_8x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE); -void kernel_dtrsm_nn_rl_inv_8x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nn_rl_one_8x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde); -void kernel_dtrsm_nn_rl_one_8x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nn_ru_inv_8x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE); -void kernel_dtrsm_nn_ru_inv_8x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nn_ru_one_8x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde); -void kernel_dtrsm_nn_ru_one_8x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nt_rl_inv_8x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE); -void kernel_dtrsm_nt_rl_inv_8x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_rl_one_8x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde); -void kernel_dtrsm_nt_rl_one_8x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nt_ru_inv_8x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE); -void kernel_dtrsm_nt_ru_inv_8x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_ru_one_8x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde); -void kernel_dtrsm_nt_ru_one_8x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, int m1, int n1); -// 4x4 -void kernel_dtrsm_nn_rl_inv_4x4_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde, double *dE); -void kernel_dtrsm_nn_rl_inv_4x4_vs_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nn_rl_one_4x4_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde); -void kernel_dtrsm_nn_rl_one_4x4_vs_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nn_ru_inv_4x4_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde, double *dE); -void kernel_dtrsm_nn_ru_inv_4x4_vs_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nn_ru_one_4x4_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde); -void kernel_dtrsm_nn_ru_one_4x4_vs_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nt_rl_inv_4x4_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde, double *dE); -void kernel_dtrsm_nt_rl_inv_4x4_vs_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_rl_one_4x4_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde); -void kernel_dtrsm_nt_rl_one_4x4_vs_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nt_ru_inv_4x4_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde, double *dE); -void kernel_dtrsm_nt_ru_inv_4x4_vs_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_ru_one_4x4_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde); -void kernel_dtrsm_nt_ru_one_4x4_vs_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde, int m1, int n1); - -// A, B, C, D column-major -// 12x4 -void kernel_dgemm_nn_12x4_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nn_12x4_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nt_12x4_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_12x4_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_tt_12x4_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_tt_12x4_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -// 4x12 -void kernel_dgemm_nn_4x12_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nn_4x12_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nt_4x12_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_4x12_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_tt_4x12_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_tt_4x12_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -// 8x4 -void kernel_dgemm_nn_8x4_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nn_8x4_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nt_8x4_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_8x4_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_tt_8x4_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_tt_8x4_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -// 4x8 -void kernel_dgemm_nn_4x8_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nn_4x8_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nt_4x8_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_4x8_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_tt_4x8_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_tt_4x8_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -// 4x4 -void kernel_dgemm_nn_4x4_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nn_4x4_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nt_4x4_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_4x4_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_tt_4x4_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_tt_4x4_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); - -// A column-major -// 12 -void kernel_dgetrf_pivot_12_lib(int m, double *pA, int lda, double *inv_diag_A, int* ipiv); -void kernel_dgetrf_pivot_12_vs_lib(int m, double *pA, int lda, double *inv_diag_A, int* ipiv, int n); -// 8 -void kernel_dgetrf_pivot_8_lib(int m, double *pA, int lda, double *inv_diag_A, int* ipiv); -void kernel_dgetrf_pivot_8_vs_lib(int m, double *pA, int lda, double *inv_diag_A, int* ipiv, int n); -// 4 -void kernel_dgetrf_pivot_4_lib(int m, double *pA, int lda, double *inv_diag_A, int* ipiv); -void kernel_dgetrf_pivot_4_vs_lib(int m, double *pA, int lda, double *inv_diag_A, int* ipiv, int n); - -// vector -void kernel_ddot_11_lib(int n, double *x, double *y, double *res); -void kernel_daxpy_11_lib(int n, double *alpha, double *x, double *y); -void kernel_drowsw_lib(int kmax, double *pA, int lda, double *pC, int ldc); - -//#endif // BLAS_API - - - -// larger kernels -// 12 -void kernel_dgemm_nt_12xn_p0_lib44cc(int n, int k, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, double *A_p, double *B_p); -void kernel_dgemm_nt_12xn_pl_lib44cc(int n, int k, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, double *A_p, double *B_p); -void kernel_dgemm_nt_mx12_p0_lib44cc(int m, int k, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, double *A_p, double *B_p); -// 8 -void kernel_dgemm_nt_8xn_p0_lib44cc(int n, int k, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, double *A_p, double *B_p); - - - -// A, B panel-major bs=8; C, D column-major -// 24x8 -void kernel_dgemm_nt_24x8_lib88cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_24x8_vs_lib88cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -// 16x8 -void kernel_dgemm_nt_16x8_lib88cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_16x8_vs_lib88cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -// 8x8 -void kernel_dgemm_nt_8x8_lib88cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_8x8_vs_lib88cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); - -// A, panel-major bs=8; B, C, D column-major -// 24x8 -void kernel_dgemm_nt_24x8_lib8ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_24x8_vs_lib8ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nn_24x8_lib8ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nn_24x8_vs_lib8ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -// 16x8 -void kernel_dgemm_nt_16x8_lib8ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_16x8_vs_lib8ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nn_16x8_lib8ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nn_16x8_vs_lib8ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -// 8x8 -void kernel_dgemm_nt_8x8_lib8ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_8x8_vs_lib8ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nn_8x8_lib8ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nn_8x8_vs_lib8ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); - -// B, panel-major bs=8; A, C, D column-major -// 8x24 -void kernel_dgemm_nt_8x24_libc8cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_8x24_vs_libc8cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_tt_8x24_libc8cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_tt_8x24_vs_libc8cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -// 8x16 -void kernel_dgemm_nt_8x16_libc8cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_8x16_vs_libc8cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_tt_8x16_libc8cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_tt_8x16_vs_libc8cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -// 8x8 -void kernel_dgemm_nt_8x8_libc8cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_8x8_vs_libc8cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_tt_8x8_libc8cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_tt_8x8_vs_libc8cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); - - -// level 2 BLAS -void kernel_dgemv_n_4_libc(int kmax, double *alpha, double *A, int lda, double *x, double *z); -void kernel_dgemv_n_4_vs_libc(int kmax, double *alpha, double *A, int lda, double *x, double *z, int km); -void kernel_dgemv_t_4_libc(int kmax, double *alpha, double *A, int lda, double *x, double *beta, double *y, double *z); -void kernel_dgemv_t_4_vs_libc(int kmax, double *alpha, double *A, int lda, double *x, double *beta, double *y, double *z, int km); -void kernel_dsymv_l_4_libc(int kmax, double *alpha, double *A, int lda, double *x, double *z); -void kernel_dsymv_l_4_vs_libc(int kmax, double *alpha, double *A, int lda, double *x, double *z, int km); -void kernel_dsymv_u_4_libc(int kmax, double *alpha, double *A, int lda, double *x, double *z); -void kernel_dsymv_u_4_vs_libc(int kmax, double *alpha, double *A, int lda, double *x, double *z, int km); -void kernel_dger_4_libc(int kmax, double *alpha, double *x, double *y, double *C, int ldc, double *D, int ldd); -void kernel_dger_4_vs_libc(int kmax, double *alpha, double *x, double *y, double *C, int ldc, double *D, int ldd, int km); - - - -// aux -void kernel_dvecld_inc1(int kmax, double *x); -void kernel_dveccp_inc1(int kmax, double *x, double *y); - -//void kernel_dgetr_nt_8_p0_lib(int kmax, double *A, int lda, double *C, int ldc, double *Ap, double *Bp); -//void kernel_dgetr_nt_8_lib(int kmax, double *A, int lda, double *C, int ldc); -//void kernel_dgetr_nt_4_lib(int kmax, double *A, int lda, double *C, int ldc); -void kernel_dgetr_tn_8_p0_lib(int kmax, double *A, int lda, double *C, int ldc, double *Ap, double *Bp); -void kernel_dgetr_tn_8_lib(int kmax, double *A, int lda, double *C, int ldc); -void kernel_dgetr_tn_4_lib(int kmax, double *A, int lda, double *C, int ldc); -void kernel_dgetr_tn_4_vs_lib(int kmax, double *A, int lda, double *C, int ldc, int m1); - - -// building blocks for blocked algorithms -// -void blasfeo_hp_dgemm_nt_m2(int m, int n, int k, double alpha, double *pA, int sda, double *pB, int sdb, double beta, double *C, int ldc, double *D, int ldd); -void blasfeo_hp_dgemm_nt_n2(int m, int n, int k, double alpha, double *pA, int sda, double *pB, int sdb, double beta, double *C, int ldc, double *D, int ldd); -// -void kernel_dpack_buffer_fn(int m, int n, double *A, int lda, double *pA, int sda); -void kernel_dpack_buffer_ft(int m, int n, double *A, int lda, double *pA, int sda); -void kernel_dpack_buffer_ln(int m, double *A, int lda, double *pA, int sda); -void kernel_dpack_buffer_lt(int m, double *A, int lda, double *pA, int sda); -void kernel_dpack_buffer_ut(int m, double *A, int lda, double *pA, int sda); - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_D_KERNEL_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_i_aux_ext_dep.h b/third_party/acados/include/blasfeo/include/blasfeo_i_aux_ext_dep.h deleted file mode 100644 index 74c3fb5c0a..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_i_aux_ext_dep.h +++ /dev/null @@ -1,69 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_I_AUX_EXT_DEP_H_ -#define BLASFEO_I_AUX_EXT_DEP_H_ - - - -#include "blasfeo_target.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -#ifdef EXT_DEP - -// i_aux_extern_depend_lib -void int_zeros(int **pA, int row, int col); -void int_zeros_align(int **pA, int row, int col); -void int_free(int *pA); -void int_free_align(int *pA); -void int_print_mat(int row, int col, int *A, int lda); -int int_print_to_string_mat(char **buf_out, int row, int col, int *A, int lda); - -#endif // EXT_DEP - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_I_AUX_EXT_DEP_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_m_aux.h b/third_party/acados/include/blasfeo/include/blasfeo_m_aux.h deleted file mode 100644 index 6248853e29..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_m_aux.h +++ /dev/null @@ -1,57 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_M_AUX_H_ -#define BLASFEO_M_AUX_H_ - -#include "blasfeo_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -void blasfeo_cvt_d2s_vec(int m, struct blasfeo_dvec *vd, int vdi, struct blasfeo_svec *vs, int vsi); -void blasfeo_cvt_s2d_vec(int m, struct blasfeo_svec *vs, int vsi, struct blasfeo_dvec *vd, int vdi); -void blasfeo_cvt_d2s_mat(int m, int n, struct blasfeo_dmat *Md, int mid, int nid, struct blasfeo_smat *Ms, int mis, int nis); -void blasfeo_cvt_s2d_mat(int m, int n, struct blasfeo_smat *Ms, int mis, int nis, struct blasfeo_dmat *Md, int mid, int nid); - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_M_AUX_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_memory.h b/third_party/acados/include/blasfeo/include/blasfeo_memory.h deleted file mode 100644 index da4e7fa090..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_memory.h +++ /dev/null @@ -1,62 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2020 by Gianluca Frison. * -* All rights reserved. * -* * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - -#ifndef BLASFEO_MEMORY_H_ -#define BLASFEO_MEMORY_H_ - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -int blasfeo_is_init(); -// -void blasfeo_init(); -// -void blasfeo_quit(); -// -void *blasfeo_get_buffer(); - - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_MEMORY_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_naming.h b/third_party/acados/include/blasfeo/include/blasfeo_naming.h deleted file mode 100644 index c289443b17..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_naming.h +++ /dev/null @@ -1,77 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - -/* - * ----------- Naming conventions - * - * (precision)(data) - * - * 1) d(double) - * s(single) - * - * 2) ge(general) - * tr(triangular) - * vec(vector) - * row(row) - * col(column) - * dia(diagonal) - * - * 3) se(set) - * cp(copy) - * sc(scale) - * ad(add) - * tr(transpose) - * in(insert) - * ex(extract) - * pe(premute) - * sw(swap) - * - * f(factorization) - * - * lqf(LQ factorization) - * qrf (factorization) - * trf (LU factorization using partial pivoting with row interchanges.) - * - * 4) _l(lower) / _u(upper) - * _lib8 (hp implementation, 8 rows kernel) - * _lib4 (hp implementation, 4 rows kernel) - * _lib0 (hp interface with reference implentation) - * _lib (reference implementation) - * _libref (reference implementation with dedicated namespace) - * - * 5) _sp(sparse) - * _exp(exponential format) - */ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_processor_features.h b/third_party/acados/include/blasfeo/include/blasfeo_processor_features.h deleted file mode 100644 index 67a0a4da04..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_processor_features.h +++ /dev/null @@ -1,88 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Ian McInerney * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_PROCESSOR_FEATURES_H_ -#define BLASFEO_PROCESSOR_FEATURES_H_ - -/** - * Flags to indicate the different processor features - */ -//enum -//{ -// // x86-64 CPU features -// BLASFEO_PROCESSOR_FEATURE_AVX = 0x0001, /// AVX instruction set -// BLASFEO_PROCESSOR_FEATURE_AVX2 = 0x0002, /// AVX2 instruction set -// BLASFEO_PROCESSOR_FEATURE_FMA = 0x0004, /// FMA instruction set -// BLASFEO_PROCESSOR_FEATURE_SSE3 = 0x0008, /// SSE3 instruction set -// -// // ARM CPU features -// BLASFEO_PROCESSOR_FEATURE_VFPv3 = 0x0100, /// VFPv3 instruction set -// BLASFEO_PROCESSOR_FEATURE_NEON = 0x0100, /// NEON instruction set -// BLASFEO_PROCESSOR_FEATURE_VFPv4 = 0x0100, /// VFPv4 instruction set -// BLASFEO_PROCESSOR_FEATURE_NEONv2 = 0x0100, /// NEONv2 instruction set -//} BLASFEO_PROCESSOR_FEATURES; - -/** - * Test the features that this processor provides against what the library was compiled with. - * - * @param features - Pointer to an integer to store the supported feature set (using the flags in the BLASFEO_PROCESSOR_FEATURES enum) - * @return 0 if current processor doesn't support all features required for this library, 1 otherwise - */ -int blasfeo_processor_cpu_features( int* features ); - -/** - * Test the features that this processor provides against what the library was compiled with. - * - * @param features - Pointer to an integer to store the supported feature set (using the flags in the BLASFEO_PROCESSOR_FEATURES enum) - * @return 0 if current processor doesn't support all features required for this library, 1 otherwise - */ -void blasfeo_processor_library_features( int* features ); - -/** - * Create a string listing the features the current processor supports. - * - * @param features - Flags from the BLASFEO_PROCESSOR_FEATURES enum indicating the features supported - * @param featureString - Character array to store the feature string in - */ -void blasfeo_processor_feature_string( int features, char* featureString ); - -/** - * Get a string listing the processor features that this library version needs to run. - * - * @param featureString - Character array to store the feature string in - */ -void blasfeo_processor_library_string( char* featureString ); - -#endif // BLASFEO_PROCESSOR_FEATURES_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_s_aux.h b/third_party/acados/include/blasfeo/include/blasfeo_s_aux.h deleted file mode 100644 index f43f5e83ce..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_s_aux.h +++ /dev/null @@ -1,168 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_S_AUX_H_ -#define BLASFEO_S_AUX_H_ - - - -#include - -#include "blasfeo_s_aux_old.h" -#include "blasfeo_common.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - -/************************************************ -* d_aux_lib.c -************************************************/ - -// returns the memory size (in bytes) needed for a smat -size_t blasfeo_memsize_smat(int m, int n); -size_t blasfeo_memsize_smat_ps(int ps, int m, int n); -// returns the memory size (in bytes) needed for the diagonal of a smat -size_t blasfeo_memsize_diag_smat(int m, int n); -// returns the memory size (in bytes) needed for a svec -size_t blasfeo_memsize_svec(int m); -// create a strmat for a matrix of size m*n by using memory passed by a pointer (pointer is not updated) -void blasfeo_create_smat(int m, int n, struct blasfeo_smat *sA, void *memory); -void blasfeo_create_smat_ps(int ps, int m, int n, struct blasfeo_smat *sA, void *memory); -// create a strvec for a vector of size m by using memory passed by a pointer (pointer is not updated) -void blasfeo_create_svec(int m, struct blasfeo_svec *sA, void *memory); -void blasfeo_pack_smat(int m, int n, float *A, int lda, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_pack_l_smat(int m, int n, float *A, int lda, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_pack_u_smat(int m, int n, float *A, int lda, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_pack_tran_smat(int m, int n, float *A, int lda, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_pack_svec(int m, float *x, int xi, struct blasfeo_svec *sa, int ai); -void blasfeo_unpack_smat(int m, int n, struct blasfeo_smat *sA, int ai, int aj, float *A, int lda); -void blasfeo_unpack_tran_smat(int m, int n, struct blasfeo_smat *sA, int ai, int aj, float *A, int lda); -void blasfeo_unpack_svec(int m, struct blasfeo_svec *sa, int ai, float *x, int xi); -//void s_cast_mat2strmat(float *A, struct blasfeo_smat *sA); -//void s_cast_diag_mat2strmat(float *dA, struct blasfeo_smat *sA); -//void s_cast_vec2vecmat(float *a, struct blasfeo_svec *sa); - -// ge -void blasfeo_sgese(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_sgecpsc(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void blasfeo_sgecp(int m, int n, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void blasfeo_sgesc(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_sgein1(float a, struct blasfeo_smat *sA, int ai, int aj); -float blasfeo_sgeex1(struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_sgead(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void blasfeo_sgetr(int m, int n, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -// tr -void blasfeo_strcp_l(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void blasfeo_strtr_l(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void blasfeo_strtr_u(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -// dia -void blasfeo_sdiare(int kmax, float alpha, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_sdiaex(int kmax, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi); -void blasfeo_sdiain(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_sdiain_sp(int kmax, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_smat *sD, int di, int dj); -void blasfeo_sdiaex_sp(int kmax, float alpha, int *idx, struct blasfeo_smat *sD, int di, int dj, struct blasfeo_svec *sx, int xi); -void blasfeo_sdiaad(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_sdiaad_sp(int kmax, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_smat *sD, int di, int dj); -void blasfeo_sdiaadin_sp(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi, int *idx, struct blasfeo_smat *sD, int di, int dj); -// row -void blasfeo_srowin(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_srowex(int kmax, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi); -void blasfeo_srowad(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_srowad_sp(int kmax, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_smat *sD, int di, int dj); -void blasfeo_srowsw(int kmax, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void blasfeo_srowpe(int kmax, int *ipiv, struct blasfeo_smat *sA); -void blasfeo_srowpei(int kmax, int *ipiv, struct blasfeo_smat *sA); -// col -void blasfeo_scolex(int kmax, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi); -void blasfeo_scolin(int kmax, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_scolad(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_scolsc(int kmax, float alpha, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_scolsw(int kmax, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void blasfeo_scolpe(int kmax, int *ipiv, struct blasfeo_smat *sA); -void blasfeo_scolpei(int kmax, int *ipiv, struct blasfeo_smat *sA); -// vec -void blasfeo_svecse(int m, float alpha, struct blasfeo_svec *sx, int xi); -void blasfeo_sveccp(int m, struct blasfeo_svec *sa, int ai, struct blasfeo_svec *sc, int ci); -void blasfeo_svecsc(int m, float alpha, struct blasfeo_svec *sa, int ai); -void blasfeo_sveccpsc(int m, float alpha, struct blasfeo_svec *sa, int ai, struct blasfeo_svec *sc, int ci); -void blasfeo_svecad(int m, float alpha, struct blasfeo_svec *sa, int ai, struct blasfeo_svec *sc, int ci); -void blasfeo_svecin1(float a, struct blasfeo_svec *sx, int xi); -float blasfeo_svecex1(struct blasfeo_svec *sx, int xi); -void blasfeo_svecad_sp(int m, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_svec *sz, int zi); -void blasfeo_svecin_sp(int m, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_svec *sz, int zi); -void blasfeo_svecex_sp(int m, float alpha, int *idx, struct blasfeo_svec *sx, int x, struct blasfeo_svec *sz, int zi); -// z += alpha * x[idx] -void blasfeo_svecexad_sp(int m, double alpha, int *idx, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -void blasfeo_sveccl(int m, struct blasfeo_svec *sxm, int xim, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sxp, int xip, struct blasfeo_svec *sz, int zi); -void blasfeo_sveccl_mask(int m, struct blasfeo_svec *sxm, int xim, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sxp, int xip, struct blasfeo_svec *sz, int zi, struct blasfeo_svec *sm, int mi); -void blasfeo_svecze(int m, struct blasfeo_svec *sm, int mi, struct blasfeo_svec *sv, int vi, struct blasfeo_svec *se, int ei); -void blasfeo_svecnrm_inf(int m, struct blasfeo_svec *sx, int xi, float *ptr_norm); -void blasfeo_svecnrm_2(int m, struct blasfeo_svec *sx, int xi, float *ptr_norm); -void blasfeo_svecpe(int kmax, int *ipiv, struct blasfeo_svec *sx, int xi); -void blasfeo_svecpei(int kmax, int *ipiv, struct blasfeo_svec *sx, int xi); - - - -/* -* Explicitly panel-major matrix format -*/ - -// returns the memory size (in bytes) needed for a dmat -size_t blasfeo_pm_memsize_smat(int ps, int m, int n); -// create a strmat for a matrix of size m*n by using memory passed by a pointer (pointer is not updated) -void blasfeo_pm_create_smat(int ps, int m, int n, struct blasfeo_pm_smat *sA, void *memory); - - - -/* -* Explicitly column-major matrix format -*/ - -// returns the memory size (in bytes) needed for a dmat -size_t blasfeo_cm_memsize_smat(int m, int n); -// create a strmat for a matrix of size m*n by using memory passed by a pointer (pointer is not updated) -void blasfeo_cm_create_smat(int m, int n, struct blasfeo_pm_smat *sA, void *memory); - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_S_AUX_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_s_aux_ext_dep.h b/third_party/acados/include/blasfeo/include/blasfeo_s_aux_ext_dep.h deleted file mode 100644 index 5209d20d37..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_s_aux_ext_dep.h +++ /dev/null @@ -1,141 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_S_AUX_EXT_DEP_H_ -#define BLASFEO_S_AUX_EXT_DEP_H_ - - - -#include - - - -#include "blasfeo_common.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -#ifdef EXT_DEP - -/************************************************ -* s_aux_extern_depend_lib.c -************************************************/ - -/* column-major matrices */ - -// dynamically allocate row*col floats of memory and set accordingly a pointer to float; set allocated memory to zero -void s_zeros(float **pA, int row, int col); -// dynamically allocate row*col floats of memory aligned to 64-byte boundaries and set accordingly a pointer to float; set allocated memory to zero -void s_zeros_align(float **pA, int row, int col); -// dynamically allocate size bytes of memory aligned to 64-byte boundaries and set accordingly a pointer to float; set allocated memory to zero -void s_zeros_align_bytes(float **pA, int size); -// free the memory allocated by d_zeros -void s_free(float *pA); -// free the memory allocated by d_zeros_align or d_zeros_align_bytes -void s_free_align(float *pA); -// print a column-major matrix -void s_print_mat(int m, int n, float *A, int lda); -// print the transposed of a column-major matrix -void s_print_tran_mat(int row, int col, float *A, int lda); -// print to file a column-major matrix -void s_print_to_file_mat(FILE *file, int row, int col, float *A, int lda); -// print to file a column-major matrix in exponential format -void s_print_to_file_exp_mat(FILE *file, int row, int col, float *A, int lda); -// print to string a column-major matrix -void s_print_to_string_mat(char **buf_out, int row, int col, float *A, int lda); -// print to file the transposed of a column-major matrix -void s_print_tran_to_file_mat(FILE *file, int row, int col, float *A, int lda); -// print to file the transposed of a column-major matrix in exponential format -void s_print_tran_to_file_exp_mat(FILE *file, int row, int col, float *A, int lda); -// print in exponential notation a column-major matrix -void s_print_exp_mat(int m, int n, float *A, int lda); -// print in exponential notation the transposed of a column-major matrix -void s_print_exp_tran_mat(int row, int col, float *A, int lda); - -/* strmat and strvec */ - -// create a strmat for a matrix of size m*n by dynamically allocating memory -void blasfeo_allocate_smat(int m, int n, struct blasfeo_smat *sA); -// create a strvec for a vector of size m by dynamically allocating memory -void blasfeo_allocate_svec(int m, struct blasfeo_svec *sa); -// free the memory allocated by blasfeo_allocate_dmat -void blasfeo_free_smat(struct blasfeo_smat *sA); -// free the memory allocated by blasfeo_allocate_dvec -void blasfeo_free_svec(struct blasfeo_svec *sa); -// print a strmat -void blasfeo_print_smat(int m, int n, struct blasfeo_smat *sA, int ai, int aj); -// print in exponential notation a strmat -void blasfeo_print_exp_smat(int m, int n, struct blasfeo_smat *sA, int ai, int aj); -// print to file a strmat -void blasfeo_print_to_file_smat(FILE *file, int m, int n, struct blasfeo_smat *sA, int ai, int aj); -// print to file a strmat in exponential format -void blasfeo_print_to_file_exp_smat(FILE *file, int m, int n, struct blasfeo_smat *sA, int ai, int aj); -// print to string a strmat -void blasfeo_print_to_string_smat(char **buf_out, int m, int n, struct blasfeo_smat *sA, int ai, int aj); -// print the transpose of a strmat -void blasfeo_print_tran_smat(int m, int n, struct blasfeo_smat *sA, int ai, int aj); -// print a strvec -void blasfeo_print_svec(int m, struct blasfeo_svec *sa, int ai); -// print in exponential notation a strvec -void blasfeo_print_exp_svec(int m, struct blasfeo_svec *sa, int ai); -// print to file a strvec -void blasfeo_print_to_file_svec(FILE *file, int m, struct blasfeo_svec *sa, int ai); -// print to string a strvec -void blasfeo_print_to_string_svec(char **buf_out, int m, struct blasfeo_svec *sa, int ai); -// print the transposed of a strvec -void blasfeo_print_tran_svec(int m, struct blasfeo_svec *sa, int ai); -// print in exponential notation the transposed of a strvec -void blasfeo_print_exp_tran_svec(int m, struct blasfeo_svec *sa, int ai); -// print to file the transposed of a strvec -void blasfeo_print_to_file_tran_svec(FILE *file, int m, struct blasfeo_svec *sa, int ai); -// print to string the transposed of a strvec -void blasfeo_print_to_string_tran_svec(char **buf_out, int m, struct blasfeo_svec *sa, int ai); - -#endif // EXT_DEP - - - -#ifdef __cplusplus -} -#endif - - - -#endif // BLASFEO_S_AUX_EXT_DEP_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_s_aux_ext_dep_ref.h b/third_party/acados/include/blasfeo/include/blasfeo_s_aux_ext_dep_ref.h deleted file mode 100644 index 6640e20a40..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_s_aux_ext_dep_ref.h +++ /dev/null @@ -1,82 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_S_AUX_EXT_DEP_REF_H_ -#define BLASFEO_S_AUX_EXT_DEP_REF_H_ - -#if defined(EXT_DEP) - - - -#include - -#include "blasfeo_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - -// expose reference BLASFEO for testing -// see blasfeo_s_aux_exp_dep.h for help - -void blasfeo_print_smat_ref(int m, int n, struct blasfeo_smat_ref *sA, int ai, int aj); -void blasfeo_allocate_smat_ref(int m, int n, struct blasfeo_smat_ref *sA); -void blasfeo_allocate_svec_ref(int m, struct blasfeo_svec_ref *sa); -void blasfeo_free_smat_ref(struct blasfeo_smat_ref *sA); -void blasfeo_free_svec_ref(struct blasfeo_svec_ref *sa); -void blasfeo_print_smat_ref(int m, int n, struct blasfeo_smat_ref *sA, int ai, int aj); -void blasfeo_print_exp_smat_ref(int m, int n, struct blasfeo_smat_ref *sA, int ai, int aj); -void blasfeo_print_to_file_smat_ref(FILE *file, int m, int n, struct blasfeo_smat_ref *sA, int ai, int aj); -void blasfeo_print_to_file_exp_smat_ref(FILE *file, int m, int n, struct blasfeo_smat_ref *sA, int ai, int aj); -void blasfeo_print_to_string_smat_ref(char **buf_out, int m, int n, struct blasfeo_smat_ref *sA, int ai, int aj); -void blasfeo_print_svec(int m, struct blasfeo_svec *sa, int ai); -void blasfeo_print_exp_svec(int m, struct blasfeo_svec *sa, int ai); -void blasfeo_print_to_file_svec(FILE *file, int m, struct blasfeo_svec *sa, int ai); -void blasfeo_print_to_string_svec(char **buf_out, int m, struct blasfeo_svec *sa, int ai); -void blasfeo_print_tran_svec(int m, struct blasfeo_svec *sa, int ai); -void blasfeo_print_exp_tran_svec(int m, struct blasfeo_svec *sa, int ai); -void blasfeo_print_to_file_tran_svec(FILE *file, int m, struct blasfeo_svec *sa, int ai); -void blasfeo_print_to_string_tran_svec(char **buf_out, int m, struct blasfeo_svec *sa, int ai); - - -#ifdef __cplusplus -} -#endif - - - -#endif // EXT_DEP - -#endif // BLASFEO_S_AUX_EXT_DEP_REF_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_s_aux_old.h b/third_party/acados/include/blasfeo/include/blasfeo_s_aux_old.h deleted file mode 100644 index 5c6db37bab..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_s_aux_old.h +++ /dev/null @@ -1,64 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -// TODO remove -// -void strcp_l_lib(int m, float alpha, int offsetA, float *A, int sda, int offsetB, float *B, int sdb); -void sgead_lib(int m, int n, float alpha, int offsetA, float *A, int sda, int offsetB, float *B, int sdb); -void sgetr_lib(int m, int n, float alpha, int offsetA, float *pA, int sda, int offsetC, float *pC, int sdc); -void strtr_l_lib(int m, float alpha, int offsetA, float *pA, int sda, int offsetC, float *pC, int sdc); -void strtr_u_lib(int m, float alpha, int offsetA, float *pA, int sda, int offsetC, float *pC, int sdc); -void sdiareg_lib(int kmax, float reg, int offset, float *pD, int sdd); -void sdiain_sqrt_lib(int kmax, float *x, int offset, float *pD, int sdd); -void sdiaex_lib(int kmax, float alpha, int offset, float *pD, int sdd, float *x); -void sdiaad_lib(int kmax, float alpha, float *x, int offset, float *pD, int sdd); -void sdiain_libsp(int kmax, int *idx, float alpha, float *x, float *pD, int sdd); -void sdiaex_libsp(int kmax, int *idx, float alpha, float *pD, int sdd, float *x); -void sdiaad_libsp(int kmax, int *idx, float alpha, float *x, float *pD, int sdd); -void sdiaadin_libsp(int kmax, int *idx, float alpha, float *x, float *y, float *pD, int sdd); -void srowin_lib(int kmax, float alpha, float *x, float *pD); -void srowex_lib(int kmax, float alpha, float *pD, float *x); -void srowad_lib(int kmax, float alpha, float *x, float *pD); -void srowin_libsp(int kmax, float alpha, int *idx, float *x, float *pD); -void srowad_libsp(int kmax, int *idx, float alpha, float *x, float *pD); -void srowadin_libsp(int kmax, int *idx, float alpha, float *x, float *y, float *pD); -void srowsw_lib(int kmax, float *pA, float *pC); -void scolin_lib(int kmax, float *x, int offset, float *pD, int sdd); -void scolad_lib(int kmax, float alpha, float *x, int offset, float *pD, int sdd); -void scolin_libsp(int kmax, int *idx, float *x, float *pD, int sdd); -void scolad_libsp(int kmax, float alpha, int *idx, float *x, float *pD, int sdd); -void scolsw_lib(int kmax, int offsetA, float *pA, int sda, int offsetC, float *pC, int sdc); -void svecin_libsp(int kmax, int *idx, float *x, float *y); -void svecad_libsp(int kmax, int *idx, float alpha, float *x, float *y); diff --git a/third_party/acados/include/blasfeo/include/blasfeo_s_aux_ref.h b/third_party/acados/include/blasfeo/include/blasfeo_s_aux_ref.h deleted file mode 100644 index 998e1d8999..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_s_aux_ref.h +++ /dev/null @@ -1,147 +0,0 @@ - -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_S_AUX_REF_H_ -#define BLASFEO_S_AUX_REF_H_ - - - -#include - -#include "blasfeo_s_aux_old.h" -#include "blasfeo_common.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - -/************************************************ -* d_aux_lib.c -************************************************/ - -// returns the memory size (in bytes) needed for a smat -size_t blasfeo_ref_memsize_smat(int m, int n); -size_t blasfeo_ref_memsize_smat_ps(int ps, int m, int n); -// returns the memory size (in bytes) needed for the diagonal of a smat -size_t blasfeo_ref_memsize_diag_smat(int m, int n); -// returns the memory size (in bytes) needed for a svec -size_t blasfeo_ref_memsize_svec(int m); -// create a strmat for a matrix of size m*n by using memory passed by a pointer (pointer is not updated) -void blasfeo_ref_create_smat(int m, int n, struct blasfeo_smat *sA, void *memory); -void blasfeo_ref_create_smat_ps(int ps, int m, int n, struct blasfeo_smat *sA, void *memory); -// create a strvec for a vector of size m by using memory passed by a pointer (pointer is not updated) -void blasfeo_ref_create_svec(int m, struct blasfeo_svec *sA, void *memory); -void blasfeo_ref_pack_smat(int m, int n, float *A, int lda, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_ref_pack_l_smat(int m, int n, float *A, int lda, struct blasfeo_smat *sB, int bi, int bj); -void blasfeo_ref_pack_l_smat(int m, int n, float *A, int lda, struct blasfeo_smat *sB, int bi, int bj); -void blasfeo_ref_pack_tran_smat(int m, int n, float *A, int lda, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_ref_pack_svec(int m, float *x, int xi, struct blasfeo_svec *sa, int ai); -void blasfeo_ref_unpack_smat(int m, int n, struct blasfeo_smat *sA, int ai, int aj, float *A, int lda); -void blasfeo_ref_unpack_tran_smat(int m, int n, struct blasfeo_smat *sA, int ai, int aj, float *A, int lda); -void blasfeo_ref_unpack_svec(int m, struct blasfeo_svec *sa, int ai, float *x, int xi); -void ref_s_cast_mat2strmat(float *A, struct blasfeo_smat *sA); -void ref_s_cast_diag_mat2strmat(float *dA, struct blasfeo_smat *sA); -void ref_s_cast_vec2vecmat(float *a, struct blasfeo_svec *sa); - -// ge -void blasfeo_ref_sgese(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_ref_sgecpsc(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void blasfeo_ref_sgecp(int m, int n, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void blasfeo_ref_sgesc(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_ref_sgein1(float a, struct blasfeo_smat *sA, int ai, int aj); -float blasfeo_ref_sgeex1(struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_ref_sgead(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void blasfeo_ref_sgetr(int m, int n, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -// tr -void blasfeo_ref_strcp_l(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void blasfeo_ref_strtr_l(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void blasfeo_ref_strtr_u(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -// dia -void blasfeo_ref_sdiare(int kmax, float alpha, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_ref_sdiaex(int kmax, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi); -void blasfeo_ref_sdiain(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_ref_sdiain_sp(int kmax, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_smat *sD, int di, int dj); -void blasfeo_ref_sdiaex_sp(int kmax, float alpha, int *idx, struct blasfeo_smat *sD, int di, int dj, struct blasfeo_svec *sx, int xi); -void blasfeo_ref_sdiaad(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_ref_sdiaad_sp(int kmax, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_smat *sD, int di, int dj); -void blasfeo_ref_sdiaadin_sp(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi, int *idx, struct blasfeo_smat *sD, int di, int dj); -// row -void blasfeo_ref_srowin(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_ref_srowex(int kmax, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi); -void blasfeo_ref_srowad(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_ref_srowad_sp(int kmax, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_smat *sD, int di, int dj); -void blasfeo_ref_srowsw(int kmax, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void blasfeo_ref_srowpe(int kmax, int *ipiv, struct blasfeo_smat *sA); -void blasfeo_ref_srowpei(int kmax, int *ipiv, struct blasfeo_smat *sA); -// col -void blasfeo_ref_scolex(int kmax, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi); -void blasfeo_ref_scolin(int kmax, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_ref_scolad(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_ref_scolsc(int kmax, float alpha, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_ref_scolsw(int kmax, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void blasfeo_ref_scolpe(int kmax, int *ipiv, struct blasfeo_smat *sA); -void blasfeo_ref_scolpei(int kmax, int *ipiv, struct blasfeo_smat *sA); -// vec -void blasfeo_ref_svecse(int m, float alpha, struct blasfeo_svec *sx, int xi); -void blasfeo_ref_sveccp(int m, struct blasfeo_svec *sa, int ai, struct blasfeo_svec *sc, int ci); -void blasfeo_ref_svecsc(int m, float alpha, struct blasfeo_svec *sa, int ai); -void blasfeo_ref_sveccpsc(int m, float alpha, struct blasfeo_svec *sa, int ai, struct blasfeo_svec *sc, int ci); -void blasfeo_ref_svecad(int m, float alpha, struct blasfeo_svec *sa, int ai, struct blasfeo_svec *sc, int ci); -void blasfeo_ref_svecin1(float a, struct blasfeo_svec *sx, int xi); -float blasfeo_ref_svecex1(struct blasfeo_svec *sx, int xi); -void blasfeo_ref_svecad_sp(int m, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_svec *sz, int zi); -void blasfeo_ref_svecin_sp(int m, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_svec *sz, int zi); -void blasfeo_ref_svecex_sp(int m, float alpha, int *idx, struct blasfeo_svec *sx, int x, struct blasfeo_svec *sz, int zi); -// z += alpha * x[idx] -void blasfeo_ref_svecexad_sp(int m, double alpha, int *idx, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -void blasfeo_ref_sveccl(int m, struct blasfeo_svec *sxm, int xim, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sxp, int xip, struct blasfeo_svec *sz, int zi); -void blasfeo_ref_sveccl_mask(int m, struct blasfeo_svec *sxm, int xim, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sxp, int xip, struct blasfeo_svec *sz, int zi, struct blasfeo_svec *sm, int mi); -void blasfeo_ref_svecze(int m, struct blasfeo_svec *sm, int mi, struct blasfeo_svec *sv, int vi, struct blasfeo_svec *se, int ei); -void blasfeo_ref_svecnrm_inf(int m, struct blasfeo_svec *sx, int xi, float *ptr_norm); -void blasfeo_ref_svecpe(int kmax, int *ipiv, struct blasfeo_svec *sx, int xi); -void blasfeo_ref_svecpei(int kmax, int *ipiv, struct blasfeo_svec *sx, int xi); - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_S_AUX_REF_H_ - diff --git a/third_party/acados/include/blasfeo/include/blasfeo_s_aux_test.h b/third_party/acados/include/blasfeo/include/blasfeo_s_aux_test.h deleted file mode 100644 index 08d9a14a6a..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_s_aux_test.h +++ /dev/null @@ -1,177 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_S_AUX_TEST_H_ -#define BLASFEO_S_AUX_TEST_H_ - -#include - -#include "blasfeo_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -/************************************************ -* d_aux_lib.c -************************************************/ - -int test_blasfeo_memsize_smat(int m, int n); -int test_blasfeo_memsize_diag_smat(int m, int n); -int test_blasfeo_memsize_svec(int m); - -void test_blasfeo_create_smat(int m, int n, struct blasfeo_smat *sA, void *memory); -void test_blasfeo_create_svec(int m, struct blasfeo_svec *sA, void *memory); - -void test_blasfeo_pack_smat(int m, int n, float *A, int lda, struct blasfeo_smat *sA, int ai, int aj); -void test_blasfeo_pack_svec(int m, float *x, int xi, struct blasfeo_svec *sa, int ai); -void test_blasfeo_pack_tran_smat(int m, int n, float *A, int lda, struct blasfeo_smat *sA, int ai, int aj); -void test_blasfeo_unpack_smat(int m, int n, struct blasfeo_smat *sA, int ai, int aj, float *A, int lda); -void test_blasfeo_unpack_svec(int m, struct blasfeo_svec *sa, int ai, float *x, int xi); -void test_blasfeo_unpack_tran_smat(int m, int n, struct blasfeo_smat *sA, int ai, int aj, float *A, int lda); - -void test_s_cast_mat2strmat(float *A, struct blasfeo_smat *sA); -void test_s_cast_diag_mat2strmat(float *dA, struct blasfeo_smat *sA); -void test_s_cast_vec2vecmat(float *a, struct blasfeo_svec *sa); -// copy and scale -void test_blasfeo_sgecpsc(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void test_blasfeo_sgecp(int m, int n, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void test_blasfeo_sgesc(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj); - -// void test_blasfeo_sgein1(float a, struct blasfeo_smat *sA, int ai, int aj); -// float test_blasfeo_sgeex1(struct blasfeo_smat *sA, int ai, int aj); -// void test_blasfeo_svecin1(float a, struct blasfeo_svec *sx, int xi); -// float test_blasfeo_svecex1(struct blasfeo_svec *sx, int xi); - -// // A <= alpha -// void test_blasfeo_sgese(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj); -// // a <= alpha -// void test_blasfeo_svecse(int m, float alpha, struct blasfeo_svec *sx, int xi); - - -// void test_blasfeo_sveccp(int m, struct blasfeo_svec *sa, int ai, struct blasfeo_svec *sc, int ci); -// void test_blasfeo_svecsc(int m, float alpha, struct blasfeo_svec *sa, int ai); - -// void test_strcp_l_lib(int m, float alpha, int offsetA, float *A, int sda, int offsetB, float *B, int sdb); -// void test_blasfeo_strcp_l(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); - -// void test_sgead_lib(int m, int n, float alpha, int offsetA, float *A, int sda, int offsetB, float *B, int sdb); -// void test_blasfeo_sgead(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -// void test_blasfeo_svecad(int m, float alpha, struct blasfeo_svec *sa, int ai, struct blasfeo_svec *sc, int ci); - -// void test_sgetr_lib(int m, int n, float alpha, int offsetA, float *pA, int sda, int offsetC, float *pC, int sdc); -// void test_blasfeo_sgetr(int m, int n, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); - -// void test_strtr_l_lib(int m, float alpha, int offsetA, float *pA, int sda, int offsetC, float *pC, int sdc); -// void test_blasfeo_strtr_l(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -// void test_strtr_u_lib(int m, float alpha, int offsetA, float *pA, int sda, int offsetC, float *pC, int sdc); -// void test_blasfeo_strtr_u(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); - -// void test_sdiareg_lib(int kmax, float reg, int offset, float *pD, int sdd); -// void test_blasfeo_sdiaex(int kmax, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi); -// void test_blasfeo_sdiain(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -// void test_sdiain_sqrt_lib(int kmax, float *x, int offset, float *pD, int sdd); -// void test_sdiaex_lib(int kmax, float alpha, int offset, float *pD, int sdd, float *x); -// void test_sdiaad_lib(int kmax, float alpha, float *x, int offset, float *pD, int sdd); -// void test_sdiain_libsp(int kmax, int *idx, float alpha, float *x, float *pD, int sdd); -// void test_blasfeo_sdiain_sp(int kmax, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_smat *sD, int di, int dj); -// void test_sdiaex_libsp(int kmax, int *idx, float alpha, float *pD, int sdd, float *x); -// void test_blasfeo_sdiaex_sp(int kmax, float alpha, int *idx, struct blasfeo_smat *sD, int di, int dj, struct blasfeo_svec *sx, int xi); -// void test_blasfeo_sdiaad(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -// void test_sdiaad_libsp(int kmax, int *idx, float alpha, float *x, float *pD, int sdd); -// void test_blasfeo_sdiaad_sp(int kmax, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_smat *sD, int di, int dj); -// void test_sdiaadin_libsp(int kmax, int *idx, float alpha, float *x, float *y, float *pD, int sdd); -// void test_blasfeo_sdiaadin_sp(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi, int *idx, struct blasfeo_smat *sD, int di, int dj); -// void test_srowin_lib(int kmax, float alpha, float *x, float *pD); -// void test_blasfeo_srowin(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -// void test_srowex_lib(int kmax, float alpha, float *pD, float *x); -// void test_blasfeo_srowex(int kmax, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi); -// void test_srowad_lib(int kmax, float alpha, float *x, float *pD); -// void test_blasfeo_srowad(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -// void test_srowin_libsp(int kmax, float alpha, int *idx, float *x, float *pD); -// void test_srowad_libsp(int kmax, int *idx, float alpha, float *x, float *pD); -// void test_blasfeo_srowad_sp(int kmax, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_smat *sD, int di, int dj); -// void test_srowadin_libsp(int kmax, int *idx, float alpha, float *x, float *y, float *pD); -// void test_srowsw_lib(int kmax, float *pA, float *pC); -// void test_blasfeo_srowsw(int kmax, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -// void test_blasfeo_srowpe(int kmax, int *ipiv, struct blasfeo_smat *sA); -// void test_scolin_lib(int kmax, float *x, int offset, float *pD, int sdd); -// void test_blasfeo_scolin(int kmax, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -// void test_scolad_lib(int kmax, float alpha, float *x, int offset, float *pD, int sdd); -// void test_scolin_libsp(int kmax, int *idx, float *x, float *pD, int sdd); -// void test_scolad_libsp(int kmax, float alpha, int *idx, float *x, float *pD, int sdd); -// void test_scolsw_lib(int kmax, int offsetA, float *pA, int sda, int offsetC, float *pC, int sdc); -// void test_blasfeo_scolsw(int kmax, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -// void test_blasfeo_scolpe(int kmax, int *ipiv, struct blasfeo_smat *sA); -// void test_svecin_libsp(int kmax, int *idx, float *x, float *y); -// void test_svecad_libsp(int kmax, int *idx, float alpha, float *x, float *y); -// void test_blasfeo_svecad_sp(int m, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_svec *sz, int zi); -// void test_blasfeo_svecin_sp(int m, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_svec *sz, int zi); -// void test_blasfeo_svecex_sp(int m, float alpha, int *idx, struct blasfeo_svec *sx, int x, struct blasfeo_svec *sz, int zi); -// void test_blasfeo_sveccl(int m, struct blasfeo_svec *sxm, int xim, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sxp, int xip, struct blasfeo_svec *sz, int zi); -// void test_blasfeo_sveccl_mask(int m, struct blasfeo_svec *sxm, int xim, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sxp, int xip, struct blasfeo_svec *sz, int zi, struct blasfeo_svec *sm, int mi); -// void test_blasfeo_svecze(int m, struct blasfeo_svec *sm, int mi, struct blasfeo_svec *sv, int vi, struct blasfeo_svec *se, int ei); -// void test_blasfeo_svecnrm_inf(int m, struct blasfeo_svec *sx, int xi, float *ptr_norm); -// void test_blasfeo_svecpe(int kmax, int *ipiv, struct blasfeo_svec *sx, int xi); - - -// ext_dep - -void test_blasfeo_allocate_smat(int m, int n, struct blasfeo_smat *sA); -void test_blasfeo_allocate_svec(int m, struct blasfeo_svec *sa); - -void test_blasfeo_free_smat(struct blasfeo_smat *sA); -void test_blasfeo_free_svec(struct blasfeo_svec *sa); - -void test_blasfeo_print_smat(int m, int n, struct blasfeo_smat *sA, int ai, int aj); -void test_blasfeo_print_svec(int m, struct blasfeo_svec *sa, int ai); -void test_blasfeo_print_tran_svec(int m, struct blasfeo_svec *sa, int ai); - -void test_blasfeo_print_to_file_smat(FILE *file, int m, int n, struct blasfeo_smat *sA, int ai, int aj); -void test_blasfeo_print_to_file_svec(FILE *file, int m, struct blasfeo_svec *sa, int ai); -void test_blasfeo_print_to_file_tran_svec(FILE *file, int m, struct blasfeo_svec *sa, int ai); - -void test_blasfeo_print_exp_smat(int m, int n, struct blasfeo_smat *sA, int ai, int aj); -void test_blasfeo_print_exp_svec(int m, struct blasfeo_svec *sa, int ai); -void test_blasfeo_print_exp_tran_svec(int m, struct blasfeo_svec *sa, int ai); - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_S_AUX_TEST_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_s_blas.h b/third_party/acados/include/blasfeo/include/blasfeo_s_blas.h deleted file mode 100644 index 200f1f51b1..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_s_blas.h +++ /dev/null @@ -1,46 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_S_BLAS_H_ -#define BLASFEO_S_BLAS_H_ - - - -#include "blasfeo_s_blasfeo_api.h" -#include "blasfeo_s_blas_api.h" - - - -#endif // BLASFEO_S_BLAS_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_s_blas_api.h b/third_party/acados/include/blasfeo/include/blasfeo_s_blas_api.h deleted file mode 100644 index cf2b3e0a2d..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_s_blas_api.h +++ /dev/null @@ -1,182 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef BLASFEO_S_BLAS_API_H_ -#define BLASFEO_S_BLAS_API_H_ - - - -#include "blasfeo_target.h" - - - -#ifdef BLAS_API -#ifdef CBLAS_API -#ifndef BLASFEO_CBLAS_ENUM -#define BLASFEO_CBLAS_ENUM -#ifdef FORTRAN_BLAS_API -#ifndef CBLAS_H -enum CBLAS_ORDER {CblasRowMajor=101, CblasColMajor=102}; -enum CBLAS_TRANSPOSE {CblasNoTrans=111, CblasTrans=112, CblasConjTrans=113}; -enum CBLAS_UPLO {CblasUpper=121, CblasLower=122}; -enum CBLAS_DIAG {CblasNonUnit=131, CblasUnit=132}; -enum CBLAS_SIDE {CblasLeft=141, CblasRight=142}; -#endif // CBLAS_H -#else // FORTRAN_BLAS_API -enum BLASFEO_CBLAS_ORDER {CblasRowMajor=101, CblasColMajor=102}; -enum BLASFEO_CBLAS_TRANSPOSE {CblasNoTrans=111, CblasTrans=112, CblasConjTrans=113}; -enum BLASFEO_CBLAS_UPLO {CblasUpper=121, CblasLower=122}; -enum BLASFEO_CBLAS_DIAG {CblasNonUnit=131, CblasUnit=132}; -enum BLASFEO_CBLAS_SIDE {CblasLeft=141, CblasRight=142}; -#endif // FORTRAN_BLAS_API -#endif // BLASFEO_CBLAS_ENUM -#endif // CBLAS_API -#endif // BLAS_API - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -#ifdef BLAS_API - - - -#ifdef FORTRAN_BLAS_API - - - -// BLAS 1 -// -void saxpy_(int *n, float *alpha, float *x, int *incx, float *y, int *incy); -// -float sdot_(int *n, float *x, int *incx, float *y, int *incy); - -// BLAS 3 -// -void sgemm_(char *ta, char *tb, int *m, int *n, int *k, float *alpha, float *A, int *lda, float *B, int *ldb, float *beta, float *C, int *ldc); -// -void strsm_(char *side, char *uplo, char *transa, char *diag, int *m, int *n, float *alpha, float *A, int *lda, float *B, int *ldb); - - - -// LAPACK -// -void spotrf_(char *uplo, int *m, float *A, int *lda, int *info); - - - -#ifdef CBLAS_API - - - -// CBLAS 1 -// -void cblas_saxpy(const int N, const float alpha, const float *X, const int incX, float *Y, const int incY); - -// CBLAS 3 -// -void cblas_sgemm(const enum CBLAS_ORDER Order, const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_TRANSPOSE TransB, const int M, const int N, const int K, const float alpha, const float *A, const int lda, const float *B, const int ldb, const float beta, float *C, const int ldc); -// -void cblas_strsm(const enum CBLAS_ORDER Order, const enum CBLAS_SIDE Side, const enum CBLAS_UPLO Uplo, const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, const int M, const int N, const float alpha, const float *A, const int lda, float *B, const int ldb); - - - -#endif // CBLAS_API - - - -#else // BLASFEO_API - - - -// BLAS 1 -// -void blasfeo_blas_saxpy(int *n, float *alpha, float *x, int *incx, float *y, int *incy); -// -float blasfeo_blas_sdot(int *n, float *x, int *incx, float *y, int *incy); - -// BLAS 3 -// -void blasfeo_blas_sgemm(char *ta, char *tb, int *m, int *n, int *k, float *alpha, float *A, int *lda, float *B, int *ldb, float *beta, float *C, int *ldc); -// -void blasfeo_blas_strsm(char *side, char *uplo, char *transa, char *diag, int *m, int *n, float *alpha, float *A, int *lda, float *B, int *ldb); - - - -// LAPACK -// -void blasfeo_lapack_spotrf(char *uplo, int *m, float *A, int *lda, int *info); - - - -#ifdef CBLAS_API - - - -// CBLAS 1 -// -void blasfeo_cblas_saxpy(const int N, const float alpha, const float *X, const int incX, float *Y, const int incY); - -// CBLAS 3 -// -void blasfeo_cblas_sgemm(const enum BLASFEO_CBLAS_ORDER Order, const enum BLASFEO_CBLAS_TRANSPOSE TransA, const enum BLASFEO_CBLAS_TRANSPOSE TransB, const int M, const int N, const int K, const float alpha, const float *A, const int lda, const float *B, const int ldb, const float beta, float *C, const int ldc); -// -void blasfeo_cblas_strsm(const enum BLASFEO_CBLAS_ORDER Order, const enum BLASFEO_CBLAS_SIDE Side, const enum BLASFEO_CBLAS_UPLO Uplo, const enum BLASFEO_CBLAS_TRANSPOSE TransA, const enum BLASFEO_CBLAS_DIAG Diag, const int M, const int N, const float alpha, const float *A, const int lda, float *B, const int ldb); - - - -#endif // CBLAS_API - - - -#endif // BLASFEO_API - - - -#endif // BLAS_API - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_S_BLAS_API_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_s_blasfeo_api.h b/third_party/acados/include/blasfeo/include/blasfeo_s_blasfeo_api.h deleted file mode 100644 index 8b98104735..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_s_blasfeo_api.h +++ /dev/null @@ -1,284 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_S_BLASFEO_API_H_ -#define BLASFEO_S_BLASFEO_API_H_ - - - -#include "blasfeo_common.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - -// -// level 1 BLAS -// - -// z = y + alpha*x -void blasfeo_saxpy(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// z = beta*y + alpha*x -void blasfeo_saxpby(int kmax, float alpha, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// z = x .* y -void blasfeo_svecmul(int m, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// z += x .* y -void blasfeo_svecmulacc(int m, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// z = x .* y, return sum(z) = x^T * y -float blasfeo_svecmuldot(int m, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// return x^T * y -float blasfeo_sdot(int m, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi); -// construct givens plane rotation -void blasfeo_srotg(float a, float b, float *c, float *s); -// apply plane rotation [a b] [c -s; s; c] to the aj0 and aj1 columns of A at row index ai -void blasfeo_scolrot(int m, struct blasfeo_smat *sA, int ai, int aj0, int aj1, float c, float s); -// apply plane rotation [c s; -s c] [a; b] to the ai0 and ai1 rows of A at column index aj -void blasfeo_srowrot(int m, struct blasfeo_smat *sA, int ai0, int ai1, int aj, float c, float s); - - - -// -// level 2 BLAS -// - -// dense - -// z <= beta * y + alpha * A * x -void blasfeo_sgemv_n(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// z <= beta * y + alpha * A' * x -void blasfeo_sgemv_t(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// z <= inv( A ) * x, A (m)x(n) -void blasfeo_strsv_lnn_mn(int m, int n, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(n) -void blasfeo_strsv_ltn_mn(int m, int n, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= inv( A ) * x, A (m)x(m) lower, not_transposed, not_unit -void blasfeo_strsv_lnn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= inv( A ) * x, A (m)x(m) lower, not_transposed, unit -void blasfeo_strsv_lnu(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(m) lower, transposed, not_unit -void blasfeo_strsv_ltn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(m) lower, transposed, unit -void blasfeo_strsv_ltu(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(m) upper, not_transposed, not_unit -void blasfeo_strsv_unn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(m) upper, transposed, not_unit -void blasfeo_strsv_utn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= A * x ; A lower triangular -void blasfeo_strmv_lnn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= A * x ; A lower triangular, unit diagonal -void blasfeo_strmv_lnu(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= A' * x ; A lower triangular -void blasfeo_strmv_ltn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= A' * x ; A lower triangular, unit diagonal -void blasfeo_strmv_ltu(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= beta * y + alpha * A * x ; A upper triangular -void blasfeo_strmv_unn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= A' * x ; A upper triangular -void blasfeo_strmv_utn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z_n <= beta_n * y_n + alpha_n * A * x_n -// z_t <= beta_t * y_t + alpha_t * A' * x_t -void blasfeo_sgemv_nt(int m, int n, float alpha_n, float alpha_t, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx_n, int xi_n, struct blasfeo_svec *sx_t, int xi_t, float beta_n, float beta_t, struct blasfeo_svec *sy_n, int yi_n, struct blasfeo_svec *sy_t, int yi_t, struct blasfeo_svec *sz_n, int zi_n, struct blasfeo_svec *sz_t, int zi_t); -// z <= beta * y + alpha * A * x, where A is symmetric and only the lower triangular patr of A is accessed -void blasfeo_ssymv_l(int m, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -void blasfeo_ssymv_l_mn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// z <= beta * y + alpha * A * x, where A is symmetric and only the upper triangular patr of A is accessed -void blasfeo_ssymv_u(int m, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// D = C + alpha * x * y^T -void blasfeo_sger(int m, int n, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); - -// diagonal - -// z <= beta * y + alpha * A * x, A diagonal -void blasfeo_sgemv_d(int m, float alpha, struct blasfeo_svec *sA, int ai, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); - - - -// -// level 3 BLAS -// - -// dense - -// D <= beta * C + alpha * A * B -void blasfeo_sgemm_nn(int m, int n, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T -void blasfeo_sgemm_nt(int m, int n, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B -void blasfeo_sgemm_tn(int m, int n, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B -void blasfeo_sgemm_tt(int m, int n, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T ; C, D lower triangular -void blasfeo_ssyrk_ln(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -void blasfeo_ssyrk_ln_mn(int m, int n, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B ; C, D lower triangular -void blasfeo_ssyrk_lt(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T ; C, D upper triangular -void blasfeo_ssyrk_un(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B ; C, D upper triangular -void blasfeo_ssyrk_ut(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^T ; B upper triangular -void blasfeo_strmm_rutn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A ; A lower triangular -void blasfeo_strmm_rlnn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A lower triangular employint explicit inverse of diagonal -void blasfeo_strsm_llnn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A lower triangular with unit diagonal -void blasfeo_strsm_llnu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A lower triangular employint explicit inverse of diagonal -void blasfeo_strsm_lltn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A lower triangular with unit diagonal -void blasfeo_strsm_lltu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A upper triangular employing explicit inverse of diagonal -void blasfeo_strsm_lunn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A upper triangular withunit diagonal -void blasfeo_strsm_lunu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A upper triangular employing explicit inverse of diagonal -void blasfeo_strsm_lutn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A upper triangular withunit diagonal -void blasfeo_strsm_lutu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A lower triangular employing explicit inverse of diagonal -void blasfeo_strsm_rlnn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A lower triangular with unit diagonal -void blasfeo_strsm_rlnu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A lower triangular employing explicit inverse of diagonal -void blasfeo_strsm_rltn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A lower triangular with unit diagonal -void blasfeo_strsm_rltu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A upper triangular employing explicit inverse of diagonal -void blasfeo_strsm_runn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A upper triangular with unit diagonal -void blasfeo_strsm_runu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A upper triangular employing explicit inverse of diagonal -void blasfeo_strsm_rutn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A upper triangular with unit diagonal -void blasfeo_strsm_rutu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T + alpha * B * A^T; C, D lower triangular -void blasfeo_ssyr2k_ln(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B + alpha * B^T * A; C, D lower triangular -void blasfeo_ssyr2k_lt(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T + alpha * B * A^T; C, D upper triangular -void blasfeo_ssyr2k_un(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B + alpha * B^T * A; C, D upper triangular -void blasfeo_ssyr2k_ut(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); - -// diagonal - -// D <= alpha * A * B + beta * C, with A diagonal (stored as strvec) -void sgemm_diag_left_ib(int m, int n, float alpha, float *dA, float *pB, int sdb, float beta, float *pC, int sdc, float *pD, int sdd); -void blasfeo_sgemm_dn(int m, int n, float alpha, struct blasfeo_svec *sA, int ai, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A * B + beta * C, with B diagonal (stored as strvec) -void blasfeo_sgemm_nd(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sB, int bi, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); - - - -// -// LAPACK -// - -// D <= chol( C ) ; C, D lower triangular -void blasfeo_spotrf_l(int m, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -void blasfeo_spotrf_l_mn(int m, int n, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= chol( C ) ; C, D upper triangular -void blasfeo_spotrf_u(int m, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= chol( C + A * B' ) ; C, D lower triangular -void blasfeo_ssyrk_spotrf_ln(int m, int k, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -void blasfeo_ssyrk_spotrf_ln_mn(int m, int n, int k, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= lu( C ) ; no pivoting -void blasfeo_sgetrf_np(int m, int n, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= lu( C ) ; row pivoting -void blasfeo_sgetrf_rp(int m, int n, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj, int *ipiv); -// D <= qr( C ) -void blasfeo_sgeqrf(int m, int n, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj, void *work); -int blasfeo_sgeqrf_worksize(int m, int n); // in bytes -// D <= Q factor, where C is the output of the LQ factorization -int blasfeo_sorglq_worksize(int m, int n, int k); // in bytes -void blasfeo_sorglq(int m, int n, int k, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj, void *work); -// D <= lq( C ) -void blasfeo_sgelqf(int m, int n, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj, void *work); -int blasfeo_sgelqf_worksize(int m, int n); // in bytes -// D <= lq( C ), positive diagonal elements -void blasfeo_sgelqf_pd(int m, int n, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj, void *work); -// [L, A] <= lq( [L, A] ), positive diagonal elements, array of matrices, with -// L lower triangular, of size (m)x(m) -// A full, of size (m)x(n1) -void blasfeo_sgelqf_pd_la(int m, int n1, struct blasfeo_smat *sL, int li, int lj, struct blasfeo_smat *sA, int ai, int aj, void *work); -// [L, L, A] <= lq( [L, L, A] ), positive diagonal elements, array of matrices, with: -// L lower triangular, of size (m)x(m) -// A full, of size (m)x(n1) -void blasfeo_sgelqf_pd_lla(int m, int n1, struct blasfeo_smat *sL0, int l0i, int l0j, struct blasfeo_smat *sL1, int l1i, int l1j, struct blasfeo_smat *sA, int ai, int aj, void *work); - - - - -// -// BLAS API helper functions -// - -#if ( defined(BLAS_API) & defined(MF_PANELMAJ) ) -// BLAS 3 -void blasfeo_cm_sgemm_nn(int m, int n, int k, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, float beta, struct blasfeo_cm_smat *sC, int ci, int cj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_sgemm_nt(int m, int n, int k, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, float beta, struct blasfeo_cm_smat *sC, int ci, int cj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_sgemm_tn(int m, int n, int k, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, float beta, struct blasfeo_cm_smat *sC, int ci, int cj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_sgemm_tt(int m, int n, int k, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, float beta, struct blasfeo_cm_smat *sC, int ci, int cj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_llnn(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_llnu(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_lltn(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_lltu(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_lunn(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_lunu(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_lutn(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_lutu(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_rlnn(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_rlnu(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_rltn(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_rltu(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_runn(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_runu(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_rutn(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_rutu(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -// LAPACK -void blasfeo_cm_spotrf_l(int m, struct blasfeo_cm_smat *sC, int ci, int cj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_spotrf_u(int m, struct blasfeo_cm_smat *sC, int ci, int cj, struct blasfeo_cm_smat *sD, int di, int dj); -#endif - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_S_BLASFEO_API_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_s_blasfeo_api_ref.h b/third_party/acados/include/blasfeo/include/blasfeo_s_blasfeo_api_ref.h deleted file mode 100644 index f429a79dc3..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_s_blasfeo_api_ref.h +++ /dev/null @@ -1,135 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_S_BLASFEO_API_REF_H_ -#define BLASFEO_S_BLASFEO_API_REF_H_ - -#include "blasfeo_common.h" - - -#ifdef __cplusplus -extern "C" { -#endif - - -// expose reference BLASFEO for testing - -// --- level 1 - -void blasfeo_saxpy_ref(int kmax, float alpha, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sy, int yi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_saxpby_ref(int kmax, float alpha, struct blasfeo_svec_ref *sx, int xi, float beta, struct blasfeo_svec_ref *sy, int yi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_svecmul_ref(int m, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sy, int yi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_svecmulacc_ref(int m, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sy, int yi, struct blasfeo_svec_ref *sz, int zi); -float blasfeo_svecmuldot_ref(int m, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sy, int yi, struct blasfeo_svec_ref *sz, int zi); -float blasfeo_sdot_ref(int m, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sy, int yi); -void blasfeo_srotg_ref(float a, float b, float *c, float *s); -void blasfeo_scolrot_ref(int m, struct blasfeo_smat_ref *sA, int ai, int aj0, int aj1, float c, float s); -void blasfeo_srowrot_ref(int m, struct blasfeo_smat_ref *sA, int ai0, int ai1, int aj, float c, float s); - - -// --- level 2 - -// dense -void blasfeo_sgemv_n_ref(int m, int n, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, float beta, struct blasfeo_svec_ref *sy, int yi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_sgemv_t_ref(int m, int n, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, float beta, struct blasfeo_svec_ref *sy, int yi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_strsv_lnn_mn_ref(int m, int n, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_strsv_ltn_mn_ref(int m, int n, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_strsv_lnn_ref(int m, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_strsv_lnu_ref(int m, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_strsv_ltn_ref(int m, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_strsv_ltu_ref(int m, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_strsv_unn_ref(int m, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_strsv_utn_ref(int m, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_strmv_unn_ref(int m, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_strmv_utn_ref(int m, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_strmv_lnn_ref(int m, int n, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_strmv_ltn_ref(int m, int n, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_strmv_lnu_ref(int m, int n, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_strmv_ltu_ref(int m, int n, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_sgemv_nt_ref(int m, int n, float alpha_n, float alpha_t, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx_n, int xi_n, struct blasfeo_svec_ref *sx_t, int xi_t, float beta_n, float beta_t, struct blasfeo_svec_ref *sy_n, int yi_n, struct blasfeo_svec_ref *sy_t, int yi_t, struct blasfeo_svec_ref *sz_n, int zi_n, struct blasfeo_svec_ref *sz_t, int zi_t); -void blasfeo_ssymv_l_ref(int m, int n, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, float beta, struct blasfeo_svec_ref *sy, int yi, struct blasfeo_svec_ref *sz, int zi); - -// diagonal -void blasfeo_sgemv_d_ref(int m, float alpha, struct blasfeo_svec_ref *sA, int ai, struct blasfeo_svec_ref *sx, int xi, float beta, struct blasfeo_svec_ref *sy, int yi, struct blasfeo_svec_ref *sz, int zi); - - -// --- level 3 - -// dense -void blasfeo_sgemm_nn_ref( int m, int n, int k, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, float beta, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_sgemm_nt_ref( int m, int n, int k, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, float beta, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_sgemm_tn_ref(int m, int n, int k, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, float beta, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_sgemm_tt_ref(int m, int n, int k, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, float beta, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); - -void blasfeo_ssyrk_ln_mn_ref( int m, int n, int k, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, float beta, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_ssyrk_ln_ref( int m, int k, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, float beta, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_ssyrk_lt_ref( int m, int k, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, float beta, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_ssyrk_un_ref( int m, int k, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, float beta, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_ssyrk_ut_ref( int m, int k, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, float beta, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); - -void blasfeo_strmm_rutn_ref( int m, int n, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_strmm_rlnn_ref( int m, int n, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_strsm_rltn_ref( int m, int n, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_strsm_rltu_ref( int m, int n, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_strsm_rutn_ref( int m, int n, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_strsm_llnu_ref( int m, int n, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_strsm_lunn_ref( int m, int n, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, struct blasfeo_smat_ref *sD, int di, int dj); - -// diagonal -void dgemm_diag_left_lib_ref(int m, int n, float alpha, float *dA, float *pB, int sdb, float beta, float *pC, int sdc, float *pD, int sdd); -void blasfeo_sgemm_dn_ref(int m, int n, float alpha, struct blasfeo_svec_ref *sA, int ai, struct blasfeo_smat_ref *sB, int bi, int bj, float beta, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_sgemm_nd_ref(int m, int n, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sB, int bi, float beta, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); - -// --- lapack - -void blasfeo_sgetrf_nopivot_ref(int m, int n, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_sgetrf_rowpivot_ref(int m, int n, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj, int *ipiv); -void blasfeo_spotrf_l_ref(int m, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_spotrf_l_mn_ref(int m, int n, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_ssyrk_dpotrf_ln_ref(int m, int k, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_ssyrk_dpotrf_ln_mn_ref(int m, int n, int k, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_sgetrf_nopivot_ref(int m, int n, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_sgetrf_rowpivot_ref(int m, int n, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj, int *ipiv); -void blasfeo_sgeqrf_ref(int m, int n, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj, void *work); -void blasfeo_sgelqf_ref(int m, int n, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj, void *work); -void blasfeo_sgelqf_pd_ref(int m, int n, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj, void *work); -void blasfeo_sgelqf_pd_la_ref(int m, int n1, struct blasfeo_smat_ref *sL, int li, int lj, struct blasfeo_smat_ref *sA, int ai, int aj, void *work); -void blasfeo_sgelqf_pd_lla_ref(int m, int n1, struct blasfeo_smat_ref *sL0, int l0i, int l0j, struct blasfeo_smat_ref *sL1, int l1i, int l1j, struct blasfeo_smat_ref *sA, int ai, int aj, void *work); - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_S_BLASFEO_API_REF_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_s_blasfeo_ref_api.h b/third_party/acados/include/blasfeo/include/blasfeo_s_blasfeo_ref_api.h deleted file mode 100644 index 17cb179695..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_s_blasfeo_ref_api.h +++ /dev/null @@ -1,252 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_S_BLASFEO_REF_API_H_ -#define BLASFEO_S_BLASFEO_REF_API_H_ - - - -#include "blasfeo_common.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - -// -// level 1 BLAS -// - -// z = y + alpha*x -void blasfeo_ref_saxpy(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// z = beta*y + alpha*x -void blasfeo_ref_saxpby(int kmax, float alpha, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// z = x .* y -void blasfeo_ref_svecmul(int m, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// z += x .* y -void blasfeo_ref_svecmulacc(int m, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// z = x .* y, return sum(z) = x^T * y -float blasfeo_ref_svecmuldot(int m, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// return x^T * y -float blasfeo_ref_sdot(int m, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi); -// construct givens plane rotation -void blasfeo_ref_srotg(float a, float b, float *c, float *s); -// apply plane rotation [a b] [c -s; s; c] to the aj0 and aj1 columns of A at row index ai -void blasfeo_ref_scolrot(int m, struct blasfeo_smat *sA, int ai, int aj0, int aj1, float c, float s); -// apply plane rotation [c s; -s c] [a; b] to the ai0 and ai1 rows of A at column index aj -void blasfeo_ref_srowrot(int m, struct blasfeo_smat *sA, int ai0, int ai1, int aj, float c, float s); - - - -// -// level 2 BLAS -// - -// dense - -// z <= beta * y + alpha * A * x -void blasfeo_ref_sgemv_n(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// z <= beta * y + alpha * A' * x -void blasfeo_ref_sgemv_t(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// z <= inv( A ) * x, A (m)x(n) -void blasfeo_ref_strsv_lnn_mn(int m, int n, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(n) -void blasfeo_ref_strsv_ltn_mn(int m, int n, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= inv( A ) * x, A (m)x(m) lower, not_transposed, not_unit -void blasfeo_ref_strsv_lnn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= inv( A ) * x, A (m)x(m) lower, not_transposed, unit -void blasfeo_ref_strsv_lnu(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(m) lower, transposed, not_unit -void blasfeo_ref_strsv_ltn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(m) lower, transposed, unit -void blasfeo_ref_strsv_ltu(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(m) upper, not_transposed, not_unit -void blasfeo_ref_strsv_unn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(m) upper, transposed, not_unit -void blasfeo_ref_strsv_utn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= A * x ; A lower triangular -void blasfeo_ref_strmv_lnn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= A * x ; A lower triangular, unit diagonal -void blasfeo_ref_strmv_lnu(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= A' * x ; A lower triangular -void blasfeo_ref_strmv_ltn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= A' * x ; A lower triangular, unit diagonal -void blasfeo_ref_strmv_ltu(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= beta * y + alpha * A * x ; A upper triangular -void blasfeo_ref_strmv_unn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= A' * x ; A upper triangular -void blasfeo_ref_strmv_utn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z_n <= beta_n * y_n + alpha_n * A * x_n -// z_t <= beta_t * y_t + alpha_t * A' * x_t -void blasfeo_ref_sgemv_nt(int m, int n, float alpha_n, float alpha_t, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx_n, int xi_n, struct blasfeo_svec *sx_t, int xi_t, float beta_n, float beta_t, struct blasfeo_svec *sy_n, int yi_n, struct blasfeo_svec *sy_t, int yi_t, struct blasfeo_svec *sz_n, int zi_n, struct blasfeo_svec *sz_t, int zi_t); -// z <= beta * y + alpha * A * x, where A is symmetric and only the lower triangular patr of A is accessed -void blasfeo_ref_ssymv_l(int m, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -void blasfeo_ref_ssymv_l_mn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// z <= beta * y + alpha * A * x, where A is symmetric and only the upper triangular patr of A is accessed -void blasfeo_ref_ssymv_u(int m, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// D = C + alpha * x * y^T -void blasfeo_ref_sger(int m, int n, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); - -// diagonal - -// z <= beta * y + alpha * A * x, A diagonal -void blasfeo_ref_sgemv_d(int m, float alpha, struct blasfeo_svec *sA, int ai, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); - - - -// -// level 3 BLAS -// - -// dense - -// D <= beta * C + alpha * A * B -void blasfeo_ref_sgemm_nn(int m, int n, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T -void blasfeo_ref_sgemm_nt(int m, int n, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B -void blasfeo_ref_sgemm_tn(int m, int n, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B -void blasfeo_ref_sgemm_tt(int m, int n, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T ; C, D lower triangular -void blasfeo_ref_ssyrk_ln(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -void blasfeo_ref_ssyrk_ln_mn(int m, int n, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B ; C, D lower triangular -void blasfeo_ref_ssyrk_lt(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T ; C, D upper triangular -void blasfeo_ref_ssyrk_un(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B ; C, D upper triangular -void blasfeo_ref_ssyrk_ut(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^T ; B upper triangular -void blasfeo_ref_strmm_rutn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A ; A lower triangular -void blasfeo_ref_strmm_rlnn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A lower triangular employint explicit inverse of diagonal -void blasfeo_ref_strsm_llnn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A lower triangular with unit diagonal -void blasfeo_ref_strsm_llnu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A lower triangular employint explicit inverse of diagonal -void blasfeo_ref_strsm_lltn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A lower triangular with unit diagonal -void blasfeo_ref_strsm_lltu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A upper triangular employing explicit inverse of diagonal -void blasfeo_ref_strsm_lunn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A upper triangular withunit diagonal -void blasfeo_ref_strsm_lunu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A upper triangular employing explicit inverse of diagonal -void blasfeo_ref_strsm_lutn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A upper triangular withunit diagonal -void blasfeo_ref_strsm_lutu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A lower triangular employing explicit inverse of diagonal -void blasfeo_ref_strsm_rlnn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A lower triangular with unit diagonal -void blasfeo_ref_strsm_rlnu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A lower triangular employing explicit inverse of diagonal -void blasfeo_ref_strsm_rltn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A lower triangular with unit diagonal -void blasfeo_ref_strsm_rltu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A upper triangular employing explicit inverse of diagonal -void blasfeo_ref_strsm_runn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A upper triangular with unit diagonal -void blasfeo_ref_strsm_runu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A upper triangular employing explicit inverse of diagonal -void blasfeo_ref_strsm_rutn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A upper triangular with unit diagonal -void blasfeo_ref_strsm_rutu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T + alpha * B * A^T ; C, D lower triangular -void blasfeo_ref_ssyr2k_ln(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B + alpha * B^T * A ; C, D lower triangular -void blasfeo_ref_ssyr2k_lt(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T + alpha * B * A^T ; C, D upper triangular -void blasfeo_ref_ssyr2k_un(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B + alpha * B^T * A ; C, D upper triangular -void blasfeo_ref_ssyr2k_ut(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); - -// diagonal - -// D <= alpha * A * B + beta * C, with A diagonal (stored as strvec) -void sgemm_diag_left_ib(int m, int n, float alpha, float *dA, float *pB, int sdb, float beta, float *pC, int sdc, float *pD, int sdd); -void blasfeo_ref_sgemm_dn(int m, int n, float alpha, struct blasfeo_svec *sA, int ai, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A * B + beta * C, with B diagonal (stored as strvec) -void blasfeo_ref_sgemm_nd(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sB, int bi, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); - - - -// -// LAPACK -// - -// D <= chol( C ) ; C, D lower triangular -void blasfeo_ref_spotrf_l(int m, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -void blasfeo_ref_spotrf_l_mn(int m, int n, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= chol( C ) ; C, D upper triangular -void blasfeo_ref_spotrf_u(int m, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= chol( C + A * B' ) ; C, D lower triangular -void blasfeo_ref_ssyrk_spotrf_ln(int m, int k, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -void blasfeo_ref_ssyrk_spotrf_ln_mn(int m, int n, int k, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= lu( C ) ; no pivoting -void blasfeo_ref_sgetrf_np(int m, int n, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= lu( C ) ; row pivoting -void blasfeo_ref_sgetrf_rp(int m, int n, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj, int *ipiv); -// D <= qr( C ) -void blasfeo_ref_sgeqrf(int m, int n, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj, void *work); -int blasfeo_ref_sgeqrf_worksize(int m, int n); // in bytes -// D <= Q factor, where C is the output of the LQ factorization -int blasfeo_ref_sorglq_worksize(int m, int n, int k); // in bytes -void blasfeo_ref_sorglq(int m, int n, int k, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj, void *work); -// D <= lq( C ) -void blasfeo_ref_sgelqf(int m, int n, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj, void *work); -int blasfeo_ref_sgelqf_worksize(int m, int n); // in bytes -// D <= lq( C ), positive diagonal elements -void blasfeo_ref_sgelqf_pd(int m, int n, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj, void *work); -// [L, A] <= lq( [L, A] ), positive diagonal elements, array of matrices, with -// L lower triangular, of size (m)x(m) -// A full, of size (m)x(n1) -void blasfeo_ref_sgelqf_pd_la(int m, int n1, struct blasfeo_smat *sL, int li, int lj, struct blasfeo_smat *sA, int ai, int aj, void *work); -// [L, L, A] <= lq( [L, L, A] ), positive diagonal elements, array of matrices, with: -// L lower triangular, of size (m)x(m) -// A full, of size (m)x(n1) -void blasfeo_ref_sgelqf_pd_lla(int m, int n1, struct blasfeo_smat *sL0, int l0i, int l0j, struct blasfeo_smat *sL1, int l1i, int l1j, struct blasfeo_smat *sA, int ai, int aj, void *work); - - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_S_BLASFEO_REF_API_H_ - diff --git a/third_party/acados/include/blasfeo/include/blasfeo_s_kernel.h b/third_party/acados/include/blasfeo/include/blasfeo_s_kernel.h deleted file mode 100644 index 99d2b28c82..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_s_kernel.h +++ /dev/null @@ -1,692 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_S_KERNEL_H_ -#define BLASFEO_S_KERNEL_H_ - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// utils -void blasfeo_align_2MB(void *ptr, void **ptr_align); -void blasfeo_align_4096_byte(void *ptr, void **ptr_align); -void blasfeo_align_64_byte(void *ptr, void **ptr_align); - - - -// -// lib8 -// - -// 24x4 -void kernel_sgemm_nt_24x4_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd); -void kernel_sgemm_nt_24x4_vs_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, int km, int kn); -void kernel_sgemm_nt_24x4_gen_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, int offsetC, float *C, int sdc, int offsetD, float *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_sgemm_nn_24x4_lib8(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, float *beta, float *C, int sdc, float *D, int sdd); -void kernel_sgemm_nn_24x4_vs_lib8(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, float *beta, float *C, int sdc, float *D, int sdd, int km, int kn); -void kernel_sgemm_nn_24x4_gen_lib8(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, float *beta, int offsetC, float *C, int sdc, int offsetD, float *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_ssyrk_nt_l_24x4_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd); -void kernel_ssyrk_nt_l_24x4_vs_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, int km, int kn); -void kernel_ssyrk_nt_l_20x4_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd); -void kernel_ssyrk_nt_l_20x4_vs_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, int km, int kn); -void kernel_spotrf_nt_l_24x4_lib8(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *inv_diag_D); -void kernel_spotrf_nt_l_24x4_vs_lib8(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *inv_diag_D, int km, int kn); -void kernel_spotrf_nt_l_20x4_lib8(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *inv_diag_D); -void kernel_spotrf_nt_l_20x4_vs_lib8(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *inv_diag_D, int km, int kn); -void kernel_strsm_nt_rl_inv_24x4_lib8(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *E, float *inv_diag_E); -void kernel_strsm_nt_rl_inv_24x4_vs_lib8(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *E, float *inv_diag_E, int km, int kn); -void kernel_sgemm_strsm_nt_rl_inv_24x4_lib8(int kp, float *Ap, int sdap, float *Bp, int km_, float *Am, int sdam, float *Bm, float *C, int sdc, float *D, int sdd, float *E, float *inv_diag_E); -void kernel_sgemm_strsm_nt_rl_inv_24x4_vs_lib8(int kp, float *Ap, int sdap, float *Bp, int km_, float *Am, int sdam, float *Bm, float *C, int sdc, float *D, int sdd, float *E, float *inv_diag_E, int km, int kn); -void kernel_ssyrk_spotrf_nt_l_20x4_vs_lib8(int kp, float *Ap, int sdap, float *Bp, int km_, float *Am, int sdam, float *Bm, float *C, int sdc, float *D, int sdd, float *inv_diag_D, int km, int kn); -void kernel_ssyrk_spotrf_nt_l_20x4_lib8(int kp, float *Ap, int sdap, float *Bp, int km_, float *Am, int sdam, float *Bm, float *C, int sdc, float *D, int sdd, float *inv_diag_D); -void kernel_ssyrk_spotrf_nt_l_24x4_vs_lib8(int kp, float *Ap, int sdap, float *Bp, int km_, float *Am, int sdam, float *Bm, float *C, int sdc, float *D, int sdd, float *inv_diag_D, int km, int kn); -void kernel_ssyrk_spotrf_nt_l_24x4_lib8(int kp, float *Ap, int sdap, float *Bp, int km_, float *Am, int sdam, float *Bm, float *C, int sdc, float *D, int sdd, float *inv_diag_D); -void kernel_strmm_nn_rl_24x4_lib8(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, float *D, int sdd); -void kernel_strmm_nn_rl_24x4_vs_lib8(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, float *D, int sdd, int km, int kn); - -// 16x8 -void kernel_sgemm_nt_16x8_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, float *spil); - -// 16x4 -void kernel_sgemm_nt_16x4_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd); -void kernel_sgemm_nt_16x4_vs_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, int km, int kn); -void kernel_sgemm_nt_16x4_gen_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, int offsetC, float *C, int sdc, int offsetD, float *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_sgemm_nn_16x4_lib8(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, float *beta, float *C, int sdc, float *D, int sdd); -void kernel_sgemm_nn_16x4_vs_lib8(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, float *beta, float *C, int sdc, float *D, int sdd, int km, int kn); -void kernel_sgemm_nn_16x4_gen_lib8(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, float *beta, int offsetC, float *C, int sdc, int offsetD, float *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_ssyrk_nt_l_16x4_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd); -void kernel_ssyrk_nt_l_16x4_vs_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, int km, int kn); -void kernel_ssyrk_nt_l_12x4_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd); -void kernel_ssyrk_nt_l_12x4_vs_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, int km, int kn); -void kernel_spotrf_nt_l_16x4_lib8(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *inv_diag_D); -void kernel_spotrf_nt_l_16x4_vs_lib8(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *inv_diag_D, int km, int kn); -void kernel_spotrf_nt_l_12x4_lib8(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *inv_diag_D); -void kernel_spotrf_nt_l_12x4_vs_lib8(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *inv_diag_D, int km, int kn); -void kernel_strsm_nt_rl_inv_16x4_lib8(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *E, float *inv_diag_E); -void kernel_strsm_nt_rl_inv_16x4_vs_lib8(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *E, float *inv_diag_E, int km, int kn); -void kernel_sgemm_strsm_nt_rl_inv_16x4_lib8(int kp, float *Ap, int sdap, float *Bp, int km_, float *Am, int sdam, float *Bm, float *C, int sdc, float *D, int sdd, float *E, float *inv_diag_E); -void kernel_sgemm_strsm_nt_rl_inv_16x4_vs_lib8(int kp, float *Ap, int sdap, float *Bp, int km_, float *Am, int sdam, float *Bm, float *C, int sdc, float *D, int sdd, float *E, float *inv_diag_E, int km, int kn); -void kernel_ssyrk_spotrf_nt_l_12x4_vs_lib8(int kp, float *Ap, int sdap, float *Bp, int km_, float *Am, int sdam, float *Bm, float *C, int sdc, float *D, int sdd, float *inv_diag_D, int km, int kn); -void kernel_ssyrk_spotrf_nt_l_12x4_lib8(int kp, float *Ap, int sdap, float *Bp, int km_, float *Am, int sdam, float *Bm, float *C, int sdc, float *D, int sdd, float *inv_diag_D); -void kernel_ssyrk_spotrf_nt_l_16x4_vs_lib8(int kp, float *Ap, int sdap, float *Bp, int km_, float *Am, int sdam, float *Bm, float *C, int sdc, float *D, int sdd, float *inv_diag_D, int km, int kn); -void kernel_ssyrk_spotrf_nt_l_16x4_lib8(int kp, float *Ap, int sdap, float *Bp, int km_, float *Am, int sdam, float *Bm, float *C, int sdc, float *D, int sdd, float *inv_diag_D); -void kernel_strmm_nn_rl_16x4_lib8(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, float *D, int sdd); -void kernel_strmm_nn_rl_16x4_vs_lib8(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, float *D, int sdd, int km, int kn); -void kernel_strmm_nn_rl_16x4_gen_lib8(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, int offsetD, float *D, int sdd, int m0, int m1, int n0, int n1); - -// 8x8 -void kernel_sgemm_nt_8x8_lib8(int k, float *alpha, float *A, float *B, float *beta, float *C, float *D); -void kernel_sgemm_nt_8x8_vs_lib8(int k, float *alpha, float *A, float *B, float *beta, float *C, float *D, int km, int kn); -void kernel_sgemm_nt_8x8_gen_lib8(int k, float *alpha, float *A, float *B, float *beta, int offsetC, float *C, int sdc, int offsetD, float *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_sgemm_nn_8x8_lib8(int k, float *alpha, float *A, int offsetB, float *B, int sdb, float *beta, float *C, float *D); -void kernel_sgemm_nn_8x8_vs_lib8(int k, float *alpha, float *A, int offsetB, float *B, int sdb, float *beta, float *C, float *D, int km, int kn); -void kernel_sgemm_nn_8x8_gen_lib8(int k, float *alpha, float *A, int offsetB, float *B, int sdb, float *beta, int offsetC, float *C, int sdc, int offsetD, float *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_ssyrk_nt_l_8x8_lib8(int k, float *alpha, float *A, float *B, float *beta, float *C, float *D); -void kernel_ssyrk_nt_l_8x8_vs_lib8(int k, float *alpha, float *A, float *B, float *beta, float *C, float *D, int km, int kn); -void kernel_spotrf_nt_l_8x8_lib8(int k, float *A, float *B, float *C, float *D, float *inv_diag_D); -void kernel_spotrf_nt_l_8x8_vs_lib8(int k, float *A, float *B, float *C, float *D, float *inv_diag_D, int km, int kn); -void kernel_strsm_nt_rl_inv_8x8_lib8(int k, float *A, float *B, float *C, float *D, float *E, float *inv_diag_E); -void kernel_strsm_nt_rl_inv_8x8_vs_lib8(int k, float *A, float *B, float *C, float *D, float *E, float *inv_diag_E, int km, int kn); -void kernel_sgemm_strsm_nt_rl_inv_8x8_lib8(int kp, float *Ap, float *Bp, int km_, float *Am, float *Bm, float *C, float *D, float *E, float *inv_diag_E); -void kernel_sgemm_strsm_nt_rl_inv_8x8_vs_lib8(int kp, float *Ap, float *Bp, int km_, float *Am, float *Bm, float *C, float *D, float *E, float *inv_diag_E, int km, int kn); -void kernel_ssyrk_spotrf_nt_l_8x8_vs_lib8(int kp, float *Ap, float *Bp, int km_, float *Am, float *Bm, float *C, float *D, float *inv_diag_D, int km, int kn); -void kernel_ssyrk_spotrf_nt_l_8x8_lib8(int kp, float *Ap, float *Bp, int km_, float *Am, float *Bm, float *C, float *D, float *inv_diag_D); - -// 8x4 -void kernel_sgemm_nt_8x4_lib8(int k, float *alpha, float *A, float *B, float *beta, float *C, float *D); -void kernel_sgemm_nt_8x4_vs_lib8(int k, float *alpha, float *A, float *B, float *beta, float *C, float *D, int km, int kn); -void kernel_sgemm_nt_8x4_gen_lib8(int k, float *alpha, float *A, float *B, float *beta, int offsetC, float *C, int sdc, int offsetD, float *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_sgemm_nn_8x4_lib8(int k, float *alpha, float *A, int offsetB, float *B, int sdb, float *beta, float *C, float *D); -void kernel_sgemm_nn_8x4_vs_lib8(int k, float *alpha, float *A, int offsetB, float *B, int sdb, float *beta, float *C, float *D, int km, int kn); -void kernel_sgemm_nn_8x4_gen_lib8(int k, float *alpha, float *A, int offsetB, float *B, int sdb, float *beta, int offsetC, float *C, int sdc, int offsetD, float *D, int sdd, int m0, int m1, int n0, int n1); -//void kernel_ssyrk_nt_l_8x4_lib8(int k, float *alpha, float *A, float *B, float *beta, float *C, float *D); -void kernel_ssyrk_nt_l_8x4_vs_lib8(int k, float *alpha, float *A, float *B, float *beta, float *C, float *D, int km, int kn); -void kernel_spotrf_nt_l_8x4_lib8(int k, float *A, float *B, float *C, float *D, float *inv_diag_D); -void kernel_spotrf_nt_l_8x4_vs_lib8(int k, float *A, float *B, float *C, float *D, float *inv_diag_D, int km, int kn); -void kernel_strsm_nt_rl_inv_8x4_lib8(int k, float *A, float *B, float *C, float *D, float *E, float *inv_diag_E); -void kernel_strsm_nt_rl_inv_8x4_vs_lib8(int k, float *A, float *B, float *C, float *D, float *E, float *inv_diag_E, int km, int kn); -void kernel_sgemm_strsm_nt_rl_inv_8x4_lib8(int kp, float *Ap, float *Bp, int km_, float *Am, float *Bm, float *C, float *D, float *E, float *inv_diag_E); -void kernel_sgemm_strsm_nt_rl_inv_8x4_vs_lib8(int kp, float *Ap, float *Bp, int km_, float *Am, float *Bm, float *C, float *D, float *E, float *inv_diag_E, int km, int kn); -void kernel_ssyrk_spotrf_nt_l_8x4_vs_lib8(int kp, float *Ap, float *Bp, int km_, float *Am, float *Bm, float *C, float *D, float *inv_diag_D, int km, int kn); -void kernel_ssyrk_spotrf_nt_l_8x4_lib8(int kp, float *Ap, float *Bp, int km_, float *Am, float *Bm, float *C, float *D, float *inv_diag_D); -void kernel_strmm_nn_rl_8x4_lib8(int k, float *alpha, float *A, int offsetB, float *B, int sdb, float *D); -void kernel_strmm_nn_rl_8x4_vs_lib8(int k, float *alpha, float *A, int offsetB, float *B, int sdb, float *D, int km, int kn); -void kernel_strmm_nn_rl_8x4_gen_lib8(int k, float *alpha, float *A, int offsetB, float *B, int sdb, int offsetD, float *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_strmm_nt_ru_8x4_lib8(int k, float *alpha, float *A, float *B, float *D); -void kernel_strmm_nt_ru_8x4_vs_lib8(int k, float *alpha, float *A, float *B, float *D, int km, int kn); - -// 4x8 -void kernel_sgemm_nt_4x8_lib8(int k, float *alpha, float *A, float *B, float *beta, float *C, float *D); -void kernel_sgemm_nt_4x8_vs_lib8(int k, float *alpha, float *A, float *B, float *beta, float *C, float *D, int km, int kn); -void kernel_sgemm_nt_4x8_gen_lib8(int k, float *alpha, float *A, float *B, float *beta, int offsetC, float *C, int sdc, int offsetD, float *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_strsm_nt_rl_inv_4x8_lib8(int k, float *A, float *B, float *C, float *D, float *E, float *inv_diag_E); -void kernel_strsm_nt_rl_inv_4x8_vs_lib8(int k, float *A, float *B, float *C, float *D, float *E, float *inv_diag_E, int km, int kn); - -// 8 -void kernel_sgemv_n_8_lib8(int k, float *alpha, float *A, float *x, float *beta, float *y, float *z); -void kernel_sgemv_n_8_vs_lib8(int k, float *alpha, float *A, float *x, float *beta, float *y, float *z, int k1); -void kernel_sgemv_n_8_gen_lib8(int kmax, float *alpha, float *A, float *x, float *beta, float *y, float *z, int k0, int k1); -void kernel_sgemv_t_8_lib8(int k, float *alpha, int offsetA, float *A, int sda, float *x, float *beta, float *y, float *z); -void kernel_sgemv_t_8_vs_lib8(int k, float *alpha, int offsetA, float *A, int sda, float *x, float *beta, float *y, float *z, int k1); -void kernel_sgemv_t_4_lib8(int k, float *alpha, int offsetA, float *A, int sda, float *x, float *beta, float *y, float *z); -void kernel_sgemv_t_4_vs_lib8(int k, float *alpha, int offsetA, float *A, int sda, float *x, float *beta, float *y, float *z, int k1); -void kernel_strsv_ln_inv_8_lib8(int k, float *A, float *inv_diag_A, float *x, float *y, float *z); -void kernel_strsv_ln_inv_8_vs_lib8(int k, float *A, float *inv_diag_A, float *x, float *y, float *z, int km, int kn); -void kernel_strsv_lt_inv_8_lib8(int k, float *A, int sda, float *inv_diag_A, float *x, float *y, float *z); -void kernel_strsv_lt_inv_8_vs_lib8(int k, float *A, int sda, float *inv_diag_A, float *x, float *y, float *z, int km, int kn); -void kernel_sgemv_nt_4_lib8(int kmax, float *alpha_n, float *alpha_t, float *A, int sda, float *x_n, float *x_t, float *beta_t, float *y_t, float *z_n, float *z_t); -void kernel_sgemv_nt_4_vs_lib8(int kmax, float *alpha_n, float *alpha_t, float *A, int sda, float *x_n, float *x_t, float *beta_t, float *y_t, float *z_n, float *z_t, int km); -void kernel_ssymv_l_4l_lib8(int kmax, float *alpha, float *A, int sda, float *x, float *z); -void kernel_ssymv_l_4r_lib8(int kmax, float *alpha, float *A, int sda, float *x, float *z); -void kernel_ssymv_l_4l_gen_lib8(int kmax, float *alpha, int offA, float *A, int sda, float *x, float *z, int km); -void kernel_ssymv_l_4r_gen_lib8(int kmax, float *alpha, int offA, float *A, int sda, float *x, float *z, int km); - -// -------- aux - -// ---- copy - -// lib4 -// -void kernel_sgecpsc_4_0_lib4(int kmax, float *alpha, float *A, float *B); -void kernel_sgecp_4_0_lib4(int kmax, float *A, float *B); - -void kernel_sgecpsc_4_1_lib4(int kmax, float *alpha, float *A0, int sda, float *B); -void kernel_sgecp_4_1_lib4(int kmax, float *A0, int sda, float *B); -void kernel_sgecpsc_4_2_lib4(int kmax, float *alpha, float *A0, int sda, float *B); -void kernel_sgecp_4_2_lib4(int kmax, float *A0, int sda, float *B); -void kernel_sgecpsc_4_3_lib4(int kmax, float *alpha, float *A0, int sda, float *B); -void kernel_sgecp_4_3_lib4(int kmax, float *A0, int sda, float *B); - -void kernel_sgecpsc_3_0_lib4(int kmax, float *alpha, float *A, float *B); -void kernel_sgecp_3_0_lib4(int kmax, float *A, float *B); -void kernel_sgecpsc_3_2_lib4(int kmax, float *alpha, float *A0, int sda, float *B); -void kernel_sgecp_3_2_lib4(int kmax, float *A0, int sda, float *B); -void kernel_sgecpsc_3_3_lib4(int kmax, float *alpha, float *A0, int sda, float *B); -void kernel_sgecp_3_3_lib4(int kmax, float *A0, int sda, float *B); - -void kernel_sgecpsc_2_0_lib4(int kmax, float *alpha, float *A, float *B); -void kernel_sgecp_2_0_lib4(int kmax, float *A, float *B); -void kernel_sgecpsc_2_3_lib4(int kmax, float *alpha, float *A0, int sda, float *B); -void kernel_sgecp_2_3_lib4(int kmax, float *A0, int sda, float *B); - -void kernel_sgecpsc_1_0_lib4(int kmax, float *alpha, float *A, float *B); -void kernel_sgecp_1_0_lib4(int kmax, float *A, float *B); - -// lib8 -// -void kernel_sgecp_8_0_lib8(int m, float *A, float *B); -void kernel_sgecp_8_0_gen_lib8(int m, float *A, float *B, int m1); -void kernel_sgecp_8_0_gen_u_lib8(int m, float *A, float *B, int m1); - -void kernel_sgesc_8_0_lib8(int m, float *alpha, float *A); -void kernel_sgesc_8_0_gen_lib8(int m, float *alpha, float *A, int m1); -void kernel_sgesc_8_0_gen_u_lib8(int m, float *alpha, float *A, int m1); - -void kernel_sgecpsc_8_0_lib8(int m, float *alpha, float *A, float *B); -void kernel_sgecpsc_8_0_gen_lib8(int m, float *alpha, float *A, float *B, int m1); -void kernel_sgecpsc_8_0_gen_u_lib8(int m, float *alpha, float *A, float *B, int m1); - -void kernel_sgecp_8_1_lib8(int m, float *A, int sda, float *B); -void kernel_sgecp_8_1_gen_lib8(int m, float *A, int sda, float *B, int m1); -void kernel_sgecpsc_8_1_lib8(int m, float *alpha, float *A, int sda, float *B); -void kernel_sgecpsc_8_1_gen_lib8(int m, float *alpha, float *A, int sda, float *B, int m1); - -void kernel_sgecp_8_2_lib8(int m, float *A, int sda, float *B); -void kernel_sgecp_8_2_gen_lib8(int m, float *A, int sda, float *B, int m1); -void kernel_sgecpsc_8_2_lib8(int m, float *alpha, float *A, int sda, float *B); -void kernel_sgecpsc_8_2_gen_lib8(int m, float *alpha, float *A, int sda, float *B, int m1); - -void kernel_sgecp_8_3_lib8(int m, float *A, int sda, float *B); -void kernel_sgecp_8_3_gen_lib8(int m, float *A, int sda, float *B, int m1); -void kernel_sgecpsc_8_3_lib8(int m, float *alpha, float *A, int sda, float *B); -void kernel_sgecpsc_8_3_gen_lib8(int m, float *alpha, float *A, int sda, float *B, int m1); - -void kernel_sgecp_8_4_lib8(int m, float *A, int sda, float *B); -void kernel_sgecp_8_4_gen_lib8(int m, float *A, int sda, float *B, int m1); -void kernel_sgecpsc_8_4_lib8(int m, float *alpha, float *A, int sda, float *B); -void kernel_sgecpsc_8_4_gen_lib8(int m, float *alpha, float *A, int sda, float *B, int m1); - -void kernel_sgecp_8_5_lib8(int m, float *A, int sda, float *B); -void kernel_sgecp_8_5_gen_lib8(int m, float *A, int sda, float *B, int m1); -void kernel_sgecpsc_8_5_lib8(int m, float *alpha, float *A, int sda, float *B); -void kernel_sgecpsc_8_5_gen_lib8(int m, float *alpha, float *A, int sda, float *B, int m1); - -void kernel_sgecp_8_6_lib8(int m, float *A, int sda, float *B); -void kernel_sgecp_8_6_gen_lib8(int m, float *A, int sda, float *B, int m1); -void kernel_sgecpsc_8_6_lib8(int m, float *alpha, float *A, int sda, float *B); -void kernel_sgecpsc_8_6_gen_lib8(int m, float *alpha, float *A, int sda, float *B, int m1); - -void kernel_sgecp_8_7_lib8(int m, float *A, int sda, float *B); -void kernel_sgecp_8_7_gen_lib8(int m, float *A, int sda, float *B, int m1); -void kernel_sgecpsc_8_7_lib8(int m, float *alpha, float *A, int sda, float *B); -void kernel_sgecpsc_8_7_gen_lib8(int m, float *alpha, float *A, int sda, float *B, int m1); - -// transpose -// -void kernel_sgetr_8_0_lib8(int m, float *A, int sda, float *B); -void kernel_sgetr_8_0_gen_lib8(int m, float *A, int sda, float *B, int m1); -void kernel_sgetr_8_1_lib8(int m, float *A, int sda, float *B); -void kernel_sgetr_8_1_gen_lib8(int m, float *A, int sda, float *B, int m1); -void kernel_sgetr_8_2_lib8(int m, float *A, int sda, float *B); -void kernel_sgetr_8_2_gen_lib8(int m, float *A, int sda, float *B, int m1); -void kernel_sgetr_8_3_lib8(int m, float *A, int sda, float *B); -void kernel_sgetr_8_3_gen_lib8(int m, float *A, int sda, float *B, int m1); -void kernel_sgetr_8_4_lib8(int m, float *A, int sda, float *B); -void kernel_sgetr_8_4_gen_lib8(int m, float *A, int sda, float *B, int m1); -void kernel_sgetr_8_5_lib8(int m, float *A, int sda, float *B); -void kernel_sgetr_8_5_gen_lib8(int m, float *A, int sda, float *B, int m1); -void kernel_sgetr_8_6_lib8(int m, float *A, int sda, float *B); -void kernel_sgetr_8_6_gen_lib8(int m, float *A, int sda, float *B, int m1); -void kernel_sgetr_8_7_lib8(int m, float *A, int sda, float *B); -void kernel_sgetr_8_7_gen_lib8(int m, float *A, int sda, float *B, int m1); - -// add -// -void kernel_sgead_8_0_lib8(int m, float *alpha, float *A, float *B); -void kernel_sgead_8_0_gen_lib8(int m, float *alpha, float *A, float *B, int m1); -void kernel_sgead_8_1_lib8(int m, float *alpha, float *A, int sda, float *B); -void kernel_sgead_8_1_gen_lib8(int m, float *alpha, float *A, int sda, float *B, int m1); -void kernel_sgead_8_2_lib8(int m, float *alpha, float *A, int sda, float *B); -void kernel_sgead_8_2_gen_lib8(int m, float *alpha, float *A, int sda, float *B, int m1); -void kernel_sgead_8_3_lib8(int m, float *alpha, float *A, int sda, float *B); -void kernel_sgead_8_3_gen_lib8(int m, float *alpha, float *A, int sda, float *B, int m1); -void kernel_sgead_8_4_lib8(int m, float *alpha, float *A, int sda, float *B); -void kernel_sgead_8_4_gen_lib8(int m, float *alpha, float *A, int sda, float *B, int m1); -void kernel_sgead_8_5_lib8(int m, float *alpha, float *A, int sda, float *B); -void kernel_sgead_8_5_gen_lib8(int m, float *alpha, float *A, int sda, float *B, int m1); -void kernel_sgead_8_6_lib8(int m, float *alpha, float *A, int sda, float *B); -void kernel_sgead_8_6_gen_lib8(int m, float *alpha, float *A, int sda, float *B, int m1); -void kernel_sgead_8_7_lib8(int m, float *alpha, float *A, int sda, float *B); -void kernel_sgead_8_7_gen_lib8(int m, float *alpha, float *A, int sda, float *B, int m1); - - -// -// lib4 -// - - - -// level 2 BLAS -// 4 -void kernel_sgemv_n_4_lib4(int k, float *alpha, float *A, float *x, float *beta, float *y, float *z); -void kernel_sgemv_n_4_vs_lib4(int k, float *alpha, float *A, float *x, float *beta, float *y, float *z, int k1); -void kernel_sgemv_n_4_gen_lib4(int kmax, float *alpha, float *A, float *x, float *beta, float *y, float *z, int k0, int k1); -void kernel_sgemv_t_4_lib4(int k, float *alpha, int offsetA, float *A, int sda, float *x, float *beta, float *y, float *z); -void kernel_sgemv_t_4_vs_lib4(int k, float *alpha, int offsetA, float *A, int sda, float *x, float *beta, float *y, float *z, int k1); -void kernel_strsv_ln_inv_4_lib4(int k, float *A, float *inv_diag_A, float *x, float *y, float *z); -void kernel_strsv_ln_inv_4_vs_lib4(int k, float *A, float *inv_diag_A, float *x, float *y, float *z, int km, int kn); -void kernel_strsv_lt_inv_4_lib4(int k, float *A, int sda, float *inv_diag_A, float *x, float *y, float *z); -void kernel_strsv_lt_inv_3_lib4(int k, float *A, int sda, float *inv_diag_A, float *x, float *y, float *z); -void kernel_strsv_lt_inv_2_lib4(int k, float *A, int sda, float *inv_diag_A, float *x, float *y, float *z); -void kernel_strsv_lt_inv_1_lib4(int k, float *A, int sda, float *inv_diag_A, float *x, float *y, float *z); -void kernel_strmv_un_4_lib4(int k, float *A, float *x, float *z); -void kernel_strmv_ut_4_lib4(int k, float *A, int sda, float *x, float *z); -void kernel_strmv_ut_4_vs_lib4(int k, float *A, int sda, float *x, float *z, int km); -void kernel_sgemv_nt_6_lib4(int kmax, float *alpha_n, float *alpha_t, float *A, int sda, float *x_n, float *x_t, float *beta_t, float *y_t, float *z_n, float *z_t); -void kernel_sgemv_nt_4_lib4(int kmax, float *alpha_n, float *alpha_t, float *A, int sda, float *x_n, float *x_t, float *beta_t, float *y_t, float *z_n, float *z_t); -void kernel_sgemv_nt_4_vs_lib4(int kmax, float *alpha_n, float *alpha_t, float *A, int sda, float *x_n, float *x_t, float *beta_t, float *y_t, float *z_n, float *z_t, int km); -void kernel_ssymv_l_4_lib4(int kmax, float *alpha, float *A, int sda, float *x_n, float *z_n); -void kernel_ssymv_l_4_gen_lib4(int kmax, float *alpha, int offA, float *A, int sda, float *x_n, float *z_n, int km); - - - -// level 3 BLAS -// 12x4 -void kernel_sgemm_nt_16x4_lib4(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd); // -void kernel_sgemm_nt_16x4_vs_lib4(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, int m1, int n1); // -void kernel_strsm_nt_rl_inv_16x4_lib4(int k, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, float *E, float *inv_diag_E); -void kernel_strsm_nt_rl_inv_16x4_vs_lib4(int k, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, float *E, float *inv_diag_E, int m1, int n1); -// 12x4 -void kernel_sgemm_nt_12x4_lib4(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd); // -void kernel_sgemm_nt_12x4_vs_lib4(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, int m1, int n1); // -void kernel_strsm_nt_rl_inv_12x4_lib4(int k, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, float *E, float *inv_diag_E); -void kernel_strsm_nt_rl_inv_12x4_vs_lib4(int k, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, float *E, float *inv_diag_E, int m1, int n1); -// 8x8 -void kernel_sgemm_nt_8x8_lib4(int k, float *alpha, float *A, int sda, float *B, int sdb, float *beta, float *C, int sdc, float *D, int sdd); // -void kernel_sgemm_nt_8x8_vs_lib4(int k, float *alpha, float *A, int sda, float *B, int sdb, float *beta, float *C, int sdc, float *D, int sdd, int m1, int n1); // -void kernel_sgemm_nn_8x8_lib4(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, float *beta, float *C, int sdc, float *D, int sdd); // -void kernel_sgemm_nn_8x8_vs_lib4(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, float *beta, float *C, int sdc, float *D, int sdd, int m1, int n1); // -// 8x4 -void kernel_sgemm_nt_8x4_lib4(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd); // -void kernel_sgemm_nt_8x4_vs_lib4(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, int m1, int n1); // -void kernel_sgemm_nn_8x4_lib4(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, float *beta, float *C, int sdc, float *D, int sdd); // -void kernel_sgemm_nn_8x4_vs_lib4(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, float *beta, float *C, int sdc, float *D, int sdd, int m1, int n1); // -void kernel_ssyrk_nt_l_8x4_lib4(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd); // -void kernel_ssyrk_nt_l_8x4_vs_lib4(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, int km, int kn); // -void kernel_strsm_nt_rl_inv_8x4_lib4(int k, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, float *E, float *inv_diag_E); -void kernel_strsm_nt_rl_inv_8x4_vs_lib4(int k, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, float *E, float *inv_diag_E, int m1, int n1); -// 4x4 -void kernel_sgemm_nt_4x4_lib4(int k, float *alpha, float *A, float *B, float *beta, float *C, float *D); // -void kernel_sgemm_nt_4x4_vs_lib4(int k, float *alpha, float *A, float *B, float *beta, float *C, float *D, int km, int kn); // -void kernel_sgemm_nt_4x4_gen_lib4(int k, float *alpha, float *A, float *B, float *beta, int offsetC, float *C, int sdc, int offsetD, float *D, int sdd, int m0, int m1, int k0, int k1); -void kernel_sgemm_nn_4x4_lib4(int k, float *alpha, float *A, int offsetB, float *B, int sdb, float *beta, float *C, float *D); // -void kernel_sgemm_nn_4x4_vs_lib4(int k, float *alpha, float *A, int offsetB, float *B, int sdb, float *beta, float *C, float *D, int km, int kn); // -void kernel_sgemm_nn_4x4_gen_lib4(int k, float *alpha, float *A, int offsetB, float *B, int sdb, float *beta, int offsetC, float *C, int sdc, int offsetD, float *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_ssyrk_nt_l_4x4_lib4(int k, float *alpha, float *A, float *B, float *beta, float *C, float *D); // -void kernel_ssyrk_nt_l_4x4_vs_lib4(int k, float *alpha, float *A, float *B, float *beta, float *C, float *D, int km, int kn); // -void kernel_ssyrk_nt_l_4x4_gen_lib4(int k, float *alpha, float *A, float *B, float *beta, int offsetC, float *C, int sdc, int offsetD, float *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_strmm_nt_ru_4x4_lib4(int k, float *alpha, float *A, float *B, float *D); // -void kernel_strmm_nt_ru_4x4_vs_lib4(int k, float *alpha, float *A, float *B, float *D, int km, int kn); // -void kernel_strmm_nn_rl_4x4_lib4(int k, float *alpha, float *A, int offsetB, float *B, int sdb, float *D); -void kernel_strmm_nn_rl_4x4_gen_lib4(int k, float *alpha, float *A, int offsetB, float *B, int sdb, int offsetD, float *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_strsm_nt_rl_inv_4x4_lib4(int k, float *A, float *B, float *beta, float *C, float *D, float *E, float *inv_diag_E); -void kernel_strsm_nt_rl_inv_4x4_vs_lib4(int k, float *A, float *B, float *beta, float *C, float *D, float *E, float *inv_diag_E, int km, int kn); -void kernel_strsm_nt_rl_one_4x4_lib4(int k, float *A, float *B, float *beta, float *C, float *D, float *E); -void kernel_strsm_nt_rl_one_4x4_vs_lib4(int k, float *A, float *B, float *beta, float *C, float *D, float *E, int km, int kn); -void kernel_strsm_nt_ru_inv_4x4_lib4(int k, float *A, float *B, float *beta, float *C, float *D, float *E, float *inv_diag_E); -void kernel_strsm_nt_ru_inv_4x4_vs_lib4(int k, float *A, float *B, float *beta, float *C, float *D, float *E, float *inv_diag_E, int km, int kn); -void kernel_strsm_nt_ru_one_4x4_lib4(int k, float *A, float *B, float *beta, float *C, float *D, float *E); -void kernel_strsm_nt_ru_one_4x4_vs_lib4(int k, float *A, float *B, float *beta, float *C, float *D, float *E, int km, int kn); -void kernel_strsm_nn_ru_inv_4x4_lib4(int k, float *A, float *B, int sdb, float *beta, float *C, float *D, float *E, float *inv_diag_E); -void kernel_strsm_nn_ru_inv_4x4_vs_lib4(int k, float *A, float *B, int sdb, float *beta, float *C, float *D, float *E, float *inv_diag_E, int km, int kn); -void kernel_strsm_nn_ll_one_4x4_lib4(int k, float *A, float *B, int sdb, float *C, float *D, float *E); -void kernel_strsm_nn_ll_one_4x4_vs_lib4(int k, float *A, float *B, int sdb, float *C, float *D, float *E, int km, int kn); -void kernel_strsm_nn_lu_inv_4x4_lib4(int kmax, float *A, float *B, int sdb, float *C, float *D, float *E, float *inv_diag_E); -void kernel_strsm_nn_lu_inv_4x4_vs_lib4(int kmax, float *A, float *B, int sdb, float *C, float *D, float *E, float *inv_diag_E, int km, int kn); -// diag -void kernel_sgemm_diag_right_4_a0_lib4(int kmax, float *alpha, float *A, int sda, float *B, float *D, int sdd); -void kernel_sgemm_diag_right_4_lib4(int kmax, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd); -void kernel_sgemm_diag_right_3_lib4(int kmax, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd); -void kernel_sgemm_diag_right_2_lib4(int kmax, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd); -void kernel_sgemm_diag_right_1_lib4(int kmax, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd); -void kernel_sgemm_diag_left_4_a0_lib4(int kmax, float *alpha, float *A, float *B, float *D); -void kernel_sgemm_diag_left_4_lib4(int kmax, float *alpha, float *A, float *B, float *beta, float *C, float *D); -void kernel_sgemm_diag_left_3_lib4(int kmax, float *alpha, float *A, float *B, float *beta, float *C, float *D); -void kernel_sgemm_diag_left_2_lib4(int kmax, float *alpha, float *A, float *B, float *beta, float *C, float *D); -void kernel_sgemm_diag_left_1_lib4(int kmax, float *alpha, float *A, float *B, float *beta, float *C, float *D); - - - -// LAPACK -// 16x4 -void kernel_spotrf_nt_l_16x4_lib4(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *inv_diag_D); -void kernel_spotrf_nt_l_16x4_vs_lib4(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *inv_diag_D, int m1, int n1); -// 12x4 -void kernel_spotrf_nt_l_12x4_lib4(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *inv_diag_D); -void kernel_spotrf_nt_l_12x4_vs_lib4(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *inv_diag_D, int m1, int n1); -// 8x4 -void kernel_spotrf_nt_l_8x4_lib4(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *inv_diag_D); -void kernel_spotrf_nt_l_8x4_vs_lib4(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *inv_diag_D, int m1, int n1); -// 4x4 -void kernel_spotrf_nt_l_4x4_lib4(int k, float *A, float *B, float *C, float *D, float *inv_diag_D); -void kernel_spotrf_nt_l_4x4_vs_lib4(int k, float *A, float *B, float *C, float *D, float *inv_diag_D, int km, int kn); -void kernel_sgetrf_nn_4x4_lib4(int k, float *A, float *B, int sdb, float *C, float *D, float *inv_diag_D); -void kernel_sgetrf_nn_4x4_vs_lib4(int k, float *A, float *B, int sdb, float *C, float *D, float *inv_diag_D, int km, int kn); -void kernel_sgetrf_pivot_4_lib4(int m, float *pA, int sda, float *inv_diag_A, int* ipiv); -void kernel_sgetrf_pivot_4_vs_lib4(int m, int n, float *pA, int sda, float *inv_diag_A, int* ipiv); - - - -// merged routines -// 4x4 -void kernel_sgemm_strsm_nt_rl_inv_4x4_lib4(int kp, float *Ap, float *Bp, int km_, float *Am, float *Bm, float *C, float *D, float *E, float *inv_diag_E); -void kernel_sgemm_strsm_nt_rl_inv_4x4_vs_lib4(int kp, float *Ap, float *Bp, int km_, float *Am, float *Bm, float *C, float *D, float *E, float *inv_diag_E, int km, int kn); -void kernel_ssyrk_spotrf_nt_l_4x4_vs_lib4(int kp, float *Ap, float *Bp, int km_, float *Am, float *Bm, float *C, float *D, float *inv_diag_D, int km, int kn); -void kernel_ssyrk_spotrf_nt_l_4x4_lib4(int kp, float *Ap, float *Bp, int km_, float *Am, float *Bm, float *C, float *D, float *inv_diag_D); - - - -// auxiliary routines -void kernel_strcp_l_4_0_lib4(int kmax, float *A, float *B); -void kernel_strcp_l_4_1_lib4(int kmax, float *A0, int sda, float *B); -void kernel_strcp_l_4_2_lib4(int kmax, float *A0, int sda, float *B); -void kernel_strcp_l_4_3_lib4(int kmax, float *A0, int sda, float *B); -void kernel_strcp_l_3_0_lib4(int kmax, float *A, float *B); -void kernel_strcp_l_3_2_lib4(int kmax, float *A0, int sda, float *B); -void kernel_strcp_l_3_3_lib4(int kmax, float *A0, int sda, float *B); -void kernel_strcp_l_2_0_lib4(int kmax, float *A, float *B); -void kernel_strcp_l_2_3_lib4(int kmax, float *A0, int sda, float *B); -void kernel_strcp_l_1_0_lib4(int kmax, float *A, float *B); -void kernel_sgead_4_0_lib4(int kmax, float *alpha, float *A, float *B); -void kernel_sgead_4_1_lib4(int kmax, float *alpha, float *A0, int sda, float *B); -void kernel_sgead_4_2_lib4(int kmax, float *alpha, float *A0, int sda, float *B); -void kernel_sgead_4_3_lib4(int kmax, float *alpha, float *A0, int sda, float *B); -void kernel_sgead_3_0_lib4(int kmax, float *alpha, float *A, float *B); -void kernel_sgead_3_2_lib4(int kmax, float *alpha, float *A0, int sda, float *B); -void kernel_sgead_3_3_lib4(int kmax, float *alpha, float *A0, int sda, float *B); -void kernel_sgead_2_0_lib4(int kmax, float *alpha, float *A, float *B); -void kernel_sgead_2_3_lib4(int kmax, float *alpha, float *A0, int sda, float *B); -void kernel_sgead_1_0_lib4(int kmax, float *alpha, float *A, float *B); -// TODO -void kernel_sgeset_4_lib4(int kmax, float alpha, float *A); -void kernel_strset_4_lib4(int kmax, float alpha, float *A); -void kernel_sgetr_4_lib4(int tri, int kmax, int kna, float alpha, float *A, float *C, int sdc); -void kernel_sgetr_3_lib4(int tri, int kmax, int kna, float alpha, float *A, float *C, int sdc); -void kernel_sgetr_2_lib4(int tri, int kmax, int kna, float alpha, float *A, float *C, int sdc); -void kernel_sgetr_1_lib4(int tri, int kmax, int kna, float alpha, float *A, float *C, int sdc); - - - -// pack -// 24 lib 8 -void kernel_spack_nn_24_lib8(int kmax, float *A, int lda, float *B, int sdb); -void kernel_spack_nn_24_vs_lib8(int kmax, float *A, int lda, float *B, int sdb, int m1); -// 16 lib 8 -void kernel_spack_nn_16_lib8(int kmax, float *A, int lda, float *B, int sdb); -void kernel_spack_nn_16_vs_lib8(int kmax, float *A, int lda, float *B, int sdb, int m1); -// 8 lib 8 -void kernel_spack_nn_8_lib8(int kmax, float *A, int lda, float *B); -void kernel_spack_nn_8_vs_lib8(int kmax, float *A, int lda, float *B, int m1); -void kernel_spack_tn_8_lib8(int kmax, float *A, int lda, float *B); -void kernel_spack_tn_8_vs_lib8(int kmax, float *A, int lda, float *B, int m1); -void kernel_spack_tt_8_lib8(int kmax, float *A, int lda, float *B, int sdb); -void kernel_spack_tt_8_vs_lib8(int kmax, float *A, int lda, float *B, int sdb, int m1); -// 8 lib 4 -void kernel_spack_nn_8_lib4(int kmax, float *A, int lda, float *B, int sdb); -void kernel_spack_nn_8_vs_lib4(int kmax, float *A, int lda, float *B, int sdb, int m1); -//void kernel_spack_tt_8_lib4(int kmax, float *A, int lda, float *B, int sdb); -// 4 -void kernel_spack_nn_4_lib4(int kmax, float *A, int lda, float *B); -void kernel_spack_nn_4_vs_lib4(int kmax, float *A, int lda, float *B, int m1); -void kernel_spack_tn_4_lib4(int kmax, float *A, int lda, float *B); -void kernel_spack_tn_4_vs_lib4(int kmax, float *A, int lda, float *B, int m1); -void kernel_spack_tt_4_lib4(int kmax, float *A, int lda, float *B, int sdb); -void kernel_spack_tt_4_vs_lib4(int kmax, float *A, int lda, float *B, int sdb, int m1); -// unpack -// 8 -void kernel_sunpack_nn_8_lib4(int kmax, float *A, int sda, float *B, int ldb); -void kernel_sunpack_nn_8_vs_lib4(int kmax, float *A, int sda, float *B, int ldb, int m1); -//void kernel_sunpack_tt_8_lib4(int kmax, float *A, int sda, float *B, int ldb); -// 4 -void kernel_sunpack_nn_4_lib4(int kmax, float *A, float *B, int ldb); -void kernel_sunpack_nn_4_vs_lib4(int kmax, float *A, float *B, int ldb, int m1); -void kernel_sunpack_nt_4_lib4(int kmax, float *A, float *B, int ldb); -void kernel_sunpack_nt_4_vs_lib4(int kmax, float *A, float *B, int ldb, int m1); -void kernel_sunpack_tt_4_lib4(int kmax, float *A, int sda, float *B, int ldb); - -// panel copy -// 4 -void kernel_spacp_nt_4_lib4(int kmax, float *A, int offsetB, float *B, int sdb); -void kernel_spacp_tn_4_lib4(int kmax, int offsetA, float *A, int sda, float *B); -void kernel_spacp_nn_4_lib4(int kmax, int offsetA, float *A, int sda, float *B); -void kernel_spacp_nn_4_vs_lib4(int kmax, int offsetA, float *A, int sda, float *B, int m1); - - - -/************************************************ -* BLAS API kernels -************************************************/ - -//#if defined(BLAS_API) - -// A, B panel-major bs=8; C, D column-major -// 24x4 -void kernel_sgemm_nt_24x4_lib88cc(int kmax, float *alpha, float *A, int sda, float *B, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_24x4_vs_lib88cc(int kmax, float *alpha, float *A, int sda, float *B, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -// 16x4 -void kernel_sgemm_nt_16x4_lib88cc(int kmax, float *alpha, float *A, int sda, float *B, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_16x4_vs_lib88cc(int kmax, float *alpha, float *A, int sda, float *B, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -// 8x8 -void kernel_sgemm_nt_8x8_lib88cc(int kmax, float *alpha, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_8x8_vs_lib88cc(int kmax, float *alpha, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_spotrf_nt_l_8x8_lib88cc(int kmax, float *A, float *B, float *C, int ldc, float *D, int ldd, float *dD); -void kernel_spotrf_nt_l_8x8_vs_lib88cc(int kmax, float *A, float *B, float *C, int ldc, float *D, int ldd, float *dD, int m1, int n1); -void kernel_strsm_nt_rl_inv_8x8_lib88ccc(int kmax, float *A, float *B, float *C, int ldc, float *D, int ldd, float *E, int lde, float *dE); -void kernel_strsm_nt_rl_inv_8x8_vs_lib88ccc(int kmax, float *A, float *B, float *C, int ldc, float *D, int ldd, float *E, int lde, float *dE, int m1, int n1); -// 8x4 -void kernel_sgemm_nt_8x4_lib88cc(int kmax, float *alpha, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_8x4_vs_lib88cc(int kmax, float *alpha, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); - -// A, B panel-major bs=4; C, D column-major -// 8x8 -void kernel_sgemm_nt_8x8_lib44cc(int kmax, float *alpha, float *A, int sda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd); -// 8x4 -void kernel_sgemm_nt_8x4_lib44cc(int kmax, float *alpha, float *A, int sda, float *B, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_8x4_vs_lib44cc(int kmax, float *alpha, float *A, int sda, float *B, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_spotrf_nt_l_8x4_lib44cc(int kmax, float *A, int sda, float *B, float *C, int ldc, float *D, int ldd, float *dD); -void kernel_strsm_nt_rl_inv_8x4_lib44ccc(int kmax, float *A, int sda, float *B, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, float *dE); -void kernel_strsm_nt_rl_inv_8x4_vs_lib44ccc(int kmax, float *A, int sda, float *B, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, float *dE, int m1, int n1); -// 4x4 -void kernel_sgemm_nt_4x4_lib44cc(int kmax, float *alpha, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_4x4_vs_lib44cc(int kmax, float *alpha, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_strsm_nt_rl_inv_4x4_lib44cc4(int kmax, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd, float *E, float *dE); -void kernel_strsm_nt_rl_inv_4x4_vs_lib44cc4(int kmax, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd, float *E, float *dE, int m1, int n1); -void kernel_strsm_nt_rl_inv_4x4_lib44ccc(int kmax, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, float *dE); -void kernel_strsm_nt_rl_inv_4x4_vs_lib44ccc(int kmax, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, float *dE, int m1, int n1); -void kernel_strsm_nt_rl_one_4x4_lib44cc4(int kmax, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd, float *E); -void kernel_strsm_nt_rl_one_4x4_vs_lib44cc4(int kmax, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd, float *E, int m1, int n1); -void kernel_strsm_nt_ru_inv_4x4_lib44cc4(int kmax, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd, float *E, float *dE); -void kernel_strsm_nt_ru_inv_4x4_vs_lib44cc4(int kmax, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd, float *E, float *dE, int m1, int n1); -void kernel_strsm_nt_ru_one_4x4_lib44cc4(int kmax, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd, float *E); -void kernel_strsm_nt_ru_one_4x4_vs_lib44cc4(int kmax, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd, float *E, int m1, int n1); -void kernel_spotrf_nt_l_4x4_lib44cc(int kmax, float *A, float *B, float *C, int ldc, float *D, int ldd, float *dD); -void kernel_spotrf_nt_l_4x4_vs_lib44cc(int kmax, float *A, float *B, float *C, int ldc, float *D, int ldd, float *dD, int m1, int n1); - -// B panel-major bs=8; A, C, D column-major -// 4x24 -void kernel_sgemm_nt_4x24_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_4x24_vs_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_tt_4x24_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_tt_4x24_vs_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -// 4x16 -void kernel_sgemm_nt_4x16_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_4x16_vs_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_tt_4x16_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_tt_4x16_vs_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -// 8x8 -void kernel_sgemm_nt_8x8_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_8x8_vs_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_tt_8x8_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_tt_8x8_vs_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -// 4x8 -void kernel_sgemm_nt_4x8_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_4x8_vs_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_tt_4x8_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_tt_4x8_vs_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); - -// B panel-major bs=4; A, C, D column-major -// 8x8 -void kernel_sgemm_nt_8x8_libc4cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_8x8_vs_libc4cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_tt_8x8_libc4cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_tt_8x8_vs_libc4cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -// 4x8 -void kernel_sgemm_nt_4x8_libc4cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_4x8_vs_libc4cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_tt_4x8_libc4cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_tt_4x8_vs_libc4cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -// 4x4 -void kernel_sgemm_nt_4x4_libc4cc(int kmax, float *alpha, float *A, int lda, float *B, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_4x4_vs_libc4cc(int kmax, float *alpha, float *A, int lda, float *B, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_tt_4x4_libc4cc(int kmax, float *alpha, float *A, int lda, float *B, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_tt_4x4_vs_libc4cc(int kmax, float *alpha, float *A, int lda, float *B, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); - -// A panel-major bs=8; B, C, D column-major -// 24x4 -void kernel_sgemm_nn_24x4_lib8ccc(int kmax, float *alpha, float *A, int lda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nn_24x4_vs_lib8ccc(int kmax, float *alpha, float *A, int lda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_nt_24x4_lib8ccc(int kmax, float *alpha, float *A, int lda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_24x4_vs_lib8ccc(int kmax, float *alpha, float *A, int lda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -// 16x4 -void kernel_sgemm_nn_16x4_lib8ccc(int kmax, float *alpha, float *A, int lda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nn_16x4_vs_lib8ccc(int kmax, float *alpha, float *A, int lda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_nt_16x4_lib8ccc(int kmax, float *alpha, float *A, int lda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_16x4_vs_lib8ccc(int kmax, float *alpha, float *A, int lda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -// 8x8 -void kernel_sgemm_nn_8x8_lib8ccc(int kmax, float *alpha, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nn_8x8_vs_lib8ccc(int kmax, float *alpha, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_nt_8x8_lib8ccc(int kmax, float *alpha, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_8x8_vs_lib8ccc(int kmax, float *alpha, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -// 8x4 -void kernel_sgemm_nn_8x4_lib8ccc(int kmax, float *alpha, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nn_8x4_vs_lib8ccc(int kmax, float *alpha, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_nt_8x4_lib8ccc(int kmax, float *alpha, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_8x4_vs_lib8ccc(int kmax, float *alpha, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); - -// A panel-major bs=4; B, C, D column-major -// 8x8 -void kernel_sgemm_nn_8x8_lib4ccc(int kmax, float *alpha, float *A, int sda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_8x8_lib4ccc(int kmax, float *alpha, float *A, int sda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -// 8x4 -void kernel_sgemm_nn_8x4_lib4ccc(int kmax, float *alpha, float *A, int sda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nn_8x4_vs_lib4ccc(int kmax, float *alpha, float *A, int sda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_nt_8x4_lib4ccc(int kmax, float *alpha, float *A, int sda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_8x4_vs_lib4ccc(int kmax, float *alpha, float *A, int sda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -// 4x4 -void kernel_sgemm_nn_4x4_lib4ccc(int kmax, float *alpha, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nn_4x4_vs_lib4ccc(int kmax, float *alpha, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_nt_4x4_lib4ccc(int kmax, float *alpha, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_4x4_vs_lib4ccc(int kmax, float *alpha, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_strsm_nn_rl_inv_4x4_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, float *dE); -void kernel_strsm_nn_rl_inv_4x4_vs_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, float *dE, int m1, int n1); -void kernel_strsm_nn_rl_one_4x4_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde); -void kernel_strsm_nn_rl_one_4x4_vs_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, int m1, int n1); -void kernel_strsm_nt_rl_inv_4x4_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, float *dE); -void kernel_strsm_nt_rl_inv_4x4_vs_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, float *dE, int m1, int n1); -void kernel_strsm_nt_rl_one_4x4_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde); -void kernel_strsm_nt_rl_one_4x4_vs_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, int m1, int n1); -void kernel_strsm_nn_ru_inv_4x4_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, float *dE); -void kernel_strsm_nn_ru_inv_4x4_vs_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, float *dE, int m1, int n1); -void kernel_strsm_nn_ru_one_4x4_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde); -void kernel_strsm_nn_ru_one_4x4_vs_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, int m1, int n1); -void kernel_strsm_nt_ru_inv_4x4_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, float *dE); -void kernel_strsm_nt_ru_inv_4x4_vs_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, float *dE, int m1, int n1); -void kernel_strsm_nt_ru_one_4x4_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde); -void kernel_strsm_nt_ru_one_4x4_vs_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, int m1, int n1); - -// A, C, D panel-major; B, E column-major -// TODO merge with above -// 4x4 -void kernel_strsm_nn_rl_inv_4x4_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde, float *dE); -void kernel_strsm_nn_rl_inv_4x4_vs_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde, float *dE, int m1, int n1); -void kernel_strsm_nn_rl_one_4x4_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde); -void kernel_strsm_nn_rl_one_4x4_vs_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde, int m1, int n1); -void kernel_strsm_nn_ru_inv_4x4_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde, float *dE); -void kernel_strsm_nn_ru_inv_4x4_vs_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde, float *dE, int m1, int n1); -void kernel_strsm_nn_ru_one_4x4_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde); -void kernel_strsm_nn_ru_one_4x4_vs_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde, int m1, int n1); -void kernel_strsm_nt_rl_inv_4x4_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde, float *dE); -void kernel_strsm_nt_rl_inv_4x4_vs_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde, float *dE, int m1, int n1); -void kernel_strsm_nt_rl_one_4x4_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde); -void kernel_strsm_nt_rl_one_4x4_vs_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde, int m1, int n1); -void kernel_strsm_nt_ru_inv_4x4_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde, float *dE); -void kernel_strsm_nt_ru_inv_4x4_vs_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde, float *dE, int m1, int n1); -void kernel_strsm_nt_ru_one_4x4_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde); -void kernel_strsm_nt_ru_one_4x4_vs_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde, int m1, int n1); - -// A, B, C, D column-major -void kernel_sgemm_nn_4x4_libcccc(int kmax, float *alpha, float *A, int lda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nn_4x4_vs_libcccc(int kmax, float *alpha, float *A, int lda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_nt_4x4_libcccc(int kmax, float *alpha, float *A, int lda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_4x4_vs_libcccc(int kmax, float *alpha, float *A, int lda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_tt_4x4_libcccc(int kmax, float *alpha, float *A, int lda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_tt_4x4_vs_libcccc(int kmax, float *alpha, float *A, int lda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); - -// vector -void kernel_sdot_11_lib(int n, float *x, float *y, float *res); -void kernel_saxpy_11_lib(int n, float *alpha, float *x, float *y); - - -//#endif // BLAS_API - - - -// larger kernels -// 24 -void kernel_sgemm_nt_24xn_p0_lib88cc(int n, int k, float *alpha, float *A, int sda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd, float *A_p, float *B_p); - - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_S_KERNEL_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_stdlib.h b/third_party/acados/include/blasfeo/include/blasfeo_stdlib.h deleted file mode 100644 index 9bd248b1d4..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_stdlib.h +++ /dev/null @@ -1,62 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_STDLIB_H_ -#define BLASFEO_STDLIB_H_ - -#ifdef __cplusplus -extern "C" { -#endif - - - -#include - -// -void blasfeo_malloc(void **ptr, size_t size); -// -void blasfeo_malloc_align(void **ptr, size_t size); -// -void blasfeo_free(void *ptr); -// -void blasfeo_free_align(void *ptr); - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_STDLIB_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_target.h b/third_party/acados/include/blasfeo/include/blasfeo_target.h deleted file mode 100644 index 51f617a649..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_target.h +++ /dev/null @@ -1,73 +0,0 @@ -#ifndef TARGET_X64_INTEL_HASWELL -#define TARGET_X64_INTEL_HASWELL -#endif - -#ifndef TARGET_NEED_FEATURE_AVX2 -#define TARGET_NEED_FEATURE_AVX2 1 -#endif - -#ifndef TARGET_NEED_FEATURE_FMA -#define TARGET_NEED_FEATURE_FMA 1 -#endif - -#ifndef TARGET_NEED_FEATURE_SSE3 -/* #undef TARGET_NEED_FEATURE_SSE3 */ -#endif - -#ifndef TARGET_NEED_FEATURE_AVX -/* #undef TARGET_NEED_FEATURE_AVX */ -#endif - -#ifndef TARGET_NEED_FEATURE_VFPv3 -/* #undef TARGET_NEED_FEATURE_VFPv3 */ -#endif - -#ifndef TARGET_NEED_FEATURE_NEON -/* #undef TARGET_NEED_FEATURE_NEON */ -#endif - -#ifndef TARGET_NEED_FEATURE_VFPv4 -/* #undef TARGET_NEED_FEATURE_VFPv4 */ -#endif - -#ifndef TARGET_NEED_FEATURE_NEONv2 -/* #undef TARGET_NEED_FEATURE_NEONv2 */ -#endif - -#ifndef LA_HIGH_PERFORMANCE -#define LA_HIGH_PERFORMANCE -#endif - -#ifndef MF_PANELMAJ -#define MF_PANELMAJ -#endif - -#ifndef EXT_DEP -#define ON 1 -#define OFF 0 -#if ON==ON -#define EXT_DEP -#endif -#undef ON -#undef OFF -#endif - -#ifndef BLAS_API -#define ON 1 -#define OFF 0 -#if OFF==ON -#define BLAS_API -#endif -#undef ON -#undef OFF -#endif - -#ifndef FORTRAN_BLAS_API -#define ON 1 -#define OFF 0 -#if OFF==ON -#define FORTRAN_BLAS_API -#endif -#undef ON -#undef OFF -#endif diff --git a/third_party/acados/include/blasfeo/include/blasfeo_timing.h b/third_party/acados/include/blasfeo/include/blasfeo_timing.h deleted file mode 100644 index 5671b888fe..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_timing.h +++ /dev/null @@ -1,114 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_TIMING_H_ -#define BLASFEO_TIMING_H_ - -//#include - -#if (defined _WIN32 || defined _WIN64) && !(defined __MINGW32__ || defined __MINGW64__) - - /* Use Windows QueryPerformanceCounter for timing. */ - #include - - /** A structure for keeping internal timer data. */ - typedef struct blasfeo_timer_ { - LARGE_INTEGER tic; - LARGE_INTEGER toc; - LARGE_INTEGER freq; - } blasfeo_timer; - -#elif(defined __APPLE__) - - #include - - /** A structure for keeping internal timer data. */ - typedef struct blasfeo_timer_ { - uint64_t tic; - uint64_t toc; - mach_timebase_info_data_t tinfo; - } blasfeo_timer; - -#elif(defined __DSPACE__) - - #include - - typedef struct blasfeo_timer_ { - double time; - } blasfeo_timer; - -#elif(defined __XILINX_NONE_ELF__ || defined __XILINX_ULTRASCALE_NONE_ELF_JAILHOUSE__) - - #include "xtime_l.h" - - typedef struct blasfeo_timer_ { - uint64_t tic; - uint64_t toc; - } blasfeo_timer; - -#else - - /* Use POSIX clock_gettime() for timing on non-Windows machines. */ - #include - - #if __STDC_VERSION__ >= 199901L // C99 Mode - - #include - #include - - typedef struct blasfeo_timer_ { - struct timeval tic; - struct timeval toc; - } blasfeo_timer; - - #else // ANSI C Mode - - /** A structure for keeping internal timer data. */ - typedef struct blasfeo_timer_ { - struct timespec tic; - struct timespec toc; - } blasfeo_timer; - - #endif // __STDC_VERSION__ >= 199901L - -#endif // (defined _WIN32 || defined _WIN64) - -/** A function for measurement of the current time. */ -void blasfeo_tic(blasfeo_timer* t); - -/** A function which returns the elapsed time. */ -double blasfeo_toc(blasfeo_timer* t); - -#endif // BLASFEO_TIMING_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_v_aux_ext_dep.h b/third_party/acados/include/blasfeo/include/blasfeo_v_aux_ext_dep.h deleted file mode 100644 index 1598551185..0000000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_v_aux_ext_dep.h +++ /dev/null @@ -1,83 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_V_AUX_EXT_DEP_H_ -#define BLASFEO_V_AUX_EXT_DEP_H_ - - - -#include "blasfeo_target.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -/************************************************ -* d_aux_extern_depend_lib.c -************************************************/ - -#ifdef EXT_DEP - -void v_zeros(void **ptrA, int size); -// dynamically allocate size bytes of memory aligned to 64-byte boundaries and set accordingly a pointer to void; set allocated memory to zero -void v_zeros_align(void **ptrA, int size); -// free the memory allocated by v_zeros -void v_free(void *ptrA); -// free the memory allocated by v_zeros_aligned -void v_free_align(void *ptrA); -// dynamically allocate size bytes of memory and set accordingly a pointer to char; set allocated memory to zero -void c_zeros(char **ptrA, int size); -// dynamically allocate size bytes of memory aligned to 64-byte boundaries and set accordingly a pointer to char; set allocated memory to zero -void c_zeros_align(char **ptrA, int size); -// free the memory allocated by c_zeros -void c_free(char *ptrA); -// free the memory allocated by c_zeros_aligned -void c_free_align(char *ptrA); - -#endif // EXT_DEP - - - -#ifdef __cplusplus -} -#endif - - - -#endif // BLASFEO_V_AUX_EXT_DEP_H_ diff --git a/third_party/acados/include/blasfeo/include/d_blas.h b/third_party/acados/include/blasfeo/include/d_blas.h deleted file mode 100644 index ffd2578da3..0000000000 --- a/third_party/acados/include/blasfeo/include/d_blas.h +++ /dev/null @@ -1,78 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifdef __cplusplus -extern "C" { -#endif - - - -// headers to reference BLAS and LAPACK routines employed in BLASFEO WR - -// level 1 -double ddot_(int *m, double *x, int *incx, double *y, int *incy); -void dcopy_(int *m, double *x, int *incx, double *y, int *incy); -void daxpy_(int *m, double *alpha, double *x, int *incx, double *y, int *incy); -void dscal_(int *m, double *alpha, double *x, int *incx); -void drot_(int *m, double *x, int *incx, double *y, int *incy, double *c, double *s); -void drotg_(double *a, double *b, double *c, double *s); - -// level 2 -void dgemv_(char *ta, int *m, int *n, double *alpha, double *A, int *lda, double *x, int *incx, double *beta, double *y, int *incy); -void dsymv_(char *uplo, int *m, double *alpha, double *A, int *lda, double *x, int *incx, double *beta, double *y, int *incy); -void dtrmv_(char *uplo, char *trans, char *diag, int *n, double *A, int *lda, double *x, int *incx); -void dtrsv_(char *uplo, char *trans, char *diag, int *n, double *A, int *lda, double *x, int *incx); -void dger_(int *m, int *n, double *alpha, double *x, int *incx, double *y, int *incy, double *A, int *lda); - -// level 3 -void dgemm_(char *ta, char *tb, int *m, int *n, int *k, double *alpha, double *A, int *lda, double *B, int *ldb, double *beta, double *C, int *ldc); -void dsyrk_(char *uplo, char *trans, int *n, int *k, double *alpha, double *A, int *lda, double *beta, double *C, int *ldc); -void dtrmm_(char *side, char *uplo, char *trans, char *diag, int *m, int *n, double *alpha, double *A, int *lda, double *B, int *ldb); -void dtrsm_(char *side, char *uplo, char *trans, char *diag, int *m, int *n, double *alpha, double *A, int *lda, double *B, int *ldb); -void dsyr2k_(char *uplo, char *trans, int *n, int *k, double *alpha, double *A, int *lda, double *B, int *ldb, double *beta, double *C, int *ldc); - -// lapack -void dpotrf_(char *uplo, int *m, double *A, int *lda, int *info); -void dgetrf_(int *m, int *n, double *A, int *lda, int *ipiv, int *info); -void dgeqrf_(int *m, int *n, double *A, int *lda, double *tau, double *work, int *lwork, int *info); -void dgeqr2_(int *m, int *n, double *A, int *lda, double *tau, double *work, int *info); -void dgelqf_(int *m, int *n, double *A, int *lda, double *tau, double *work, int *lwork, int *info); -void dorglq_(int *m, int *n, int *k, double *A, int *lda, double *tau, double *work, int *lwork, int *info); - - - -#ifdef __cplusplus -} -#endif diff --git a/third_party/acados/include/blasfeo/include/d_blas_64.h b/third_party/acados/include/blasfeo/include/d_blas_64.h deleted file mode 100644 index 4f40d00dfb..0000000000 --- a/third_party/acados/include/blasfeo/include/d_blas_64.h +++ /dev/null @@ -1,73 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifdef __cplusplus -extern "C" { -#endif - - - -// headers to reference BLAS and LAPACK routines employed in BLASFEO WR - -// level 1 -double ddot_(long long *m, double *x, long long *incx, double *y, long long *incy); -void dcopy_(long long *m, double *x, long long *incx, double *y, long long *incy); -void daxpy_(long long *m, double *alpha, double *x, long long *incx, double *y, long long *incy); -void dscal_(long long *m, double *alpha, double *x, long long *incx); - -// level 2 -void dgemv_(char *ta, long long *m, long long *n, double *alpha, double *A, long long *lda, double *x, long long *incx, double *beta, double *y, long long *incy); -void dsymv_(char *uplo, long long *m, double *alpha, double *A, long long *lda, double *x, long long *incx, double *beta, double *y, long long *incy); -void dtrmv_(char *uplo, char *trans, char *diag, long long *n, double *A, long long *lda, double *x, long long *incx); -void dtrsv_(char *uplo, char *trans, char *diag, long long *n, double *A, long long *lda, double *x, long long *incx); -void dger_(long long *m, long long *n, double *alpha, double *x, long long *incx, double *y, long long *incy, double *A, long long *lda); - -// level 3 -void dgemm_(char *ta, char *tb, long long *m, long long *n, long long *k, double *alpha, double *A, long long *lda, double *B, long long *ldb, double *beta, double *C, long long *ldc); -void dsyrk_(char *uplo, char *trans, long long *n, long long *k, double *alpha, double *A, long long *lda, double *beta, double *C, long long *ldc); -void dtrmm_(char *side, char *uplo, char *trans, char *diag, long long *m, long long *n, double *alpha, double *A, long long *lda, double *B, long long *ldb); -void dtrsm_(char *side, char *uplo, char *trans, char *diag, long long *m, long long *n, double *alpha, double *A, long long *lda, double *B, long long *ldb); - -// lapack -void dpotrf_(char *uplo, long long *m, double *A, long long *lda, long long *info); -void dgetrf_(long long *m, long long *n, double *A, long long *lda, long long *ipiv, long long *info); -void dgeqrf_(long long *m, long long *n, double *A, long long *lda, double *tau, double *work, long long *lwork, long long *info); -void dgeqr2_(long long *m, long long *n, double *A, long long *lda, double *tau, double *work, long long *info); - - - -#ifdef __cplusplus -} -#endif diff --git a/third_party/acados/include/blasfeo/include/s_blas.h b/third_party/acados/include/blasfeo/include/s_blas.h deleted file mode 100644 index 3b299ce64c..0000000000 --- a/third_party/acados/include/blasfeo/include/s_blas.h +++ /dev/null @@ -1,78 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifdef __cplusplus -extern "C" { -#endif - - - -// headers to reference BLAS and LAPACK routines employed in BLASFEO WR - -// level 1 -float sdot_(int *m, float *x, int *incx, float *y, int *incy); -void scopy_(int *m, float *x, int *incx, float *y, int *incy); -void saxpy_(int *m, float *alpha, float *x, int *incx, float *y, int *incy); -void sscal_(int *m, float *alpha, float *x, int *incx); -void srot_(int *m, float *x, int *incx, float *y, int *incy, float *c, float *s); -void srotg_(float *a, float *b, float *c, float *s); - -// level 2 -void sgemv_(char *ta, int *m, int *n, float *alpha, float *A, int *lda, float *x, int *incx, float *beta, float *y, int *incy); -void ssymv_(char *uplo, int *m, float *alpha, float *A, int *lda, float *x, int *incx, float *beta, float *y, int *incy); -void strmv_(char *uplo, char *trans, char *diag, int *n, float *A, int *lda, float *x, int *incx); -void strsv_(char *uplo, char *trans, char *diag, int *n, float *A, int *lda, float *x, int *incx); -void sger_(int *m, int *n, float *alpha, float *x, int *incx, float *y, int *incy, float *A, int *lda); - -// level 3 -void sgemm_(char *ta, char *tb, int *m, int *n, int *k, float *alpha, float *A, int *lda, float *B, int *ldb, float *beta, float *C, int *ldc); -void ssyrk_(char *uplo, char *trans, int *n, int *k, float *alpha, float *A, int *lda, float *beta, float *C, int *ldc); -void strmm_(char *side, char *uplo, char *transa, char *diag, int *m, int *n, float *alpha, float *A, int *lda, float *B, int *ldb); -void strsm_(char *side, char *uplo, char *transa, char *diag, int *m, int *n, float *alpha, float *A, int *lda, float *B, int *ldb); -void ssyr2k_(char *uplo, char *trans, int *n, int *k, float *alpha, float *A, int *lda, float *B, int *ldb, float *beta, float *C, int *ldc); - -// lapack -void spotrf_(char *uplo, int *m, float *A, int *lda, int *info); -void sgetrf_(int *m, int *n, float *A, int *lda, int *ipiv, int *info); -void sgeqrf_(int *m, int *n, float *A, int *lda, float *tau, float *work, int *lwork, int *info); -void sgeqr2_(int *m, int *n, float *A, int *lda, float *tau, float *work, int *info); -void sgelqf_(int *m, int *n, float *A, int *lda, float *tau, float *work, int *lwork, int *info); -void sorglq_(int *m, int *n, int *k, float *A, int *lda, float *tau, float *work, int *lwork, int *info); - - - -#ifdef __cplusplus -} -#endif diff --git a/third_party/acados/include/blasfeo/include/s_blas_64.h b/third_party/acados/include/blasfeo/include/s_blas_64.h deleted file mode 100644 index b9efab6c23..0000000000 --- a/third_party/acados/include/blasfeo/include/s_blas_64.h +++ /dev/null @@ -1,73 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifdef __cplusplus -extern "C" { -#endif - - - -// headers to reference BLAS and LAPACK routines employed in BLASFEO WR - -// level 1 -float sdot_(long long *m, float *x, long long *incx, float *y, long long *incy); -void scopy_(long long *m, float *x, long long *incx, float *y, long long *incy); -void saxpy_(long long *m, float *alpha, float *x, long long *incx, float *y, long long *incy); -void sscal_(long long *m, float *alpha, float *x, long long *incx); - -// level 2 -void sgemv_(char *ta, long long *m, long long *n, float *alpha, float *A, long long *lda, float *x, long long *incx, float *beta, float *y, long long *incy); -void ssymv_(char *uplo, long long *m, float *alpha, float *A, long long *lda, float *x, long long *incx, float *beta, float *y, long long *incy); -void strmv_(char *uplo, char *trans, char *diag, long long *n, float *A, long long *lda, float *x, long long *incx); -void strsv_(char *uplo, char *trans, char *diag, long long *n, float *A, long long *lda, float *x, long long *incx); -void sger_(long long *m, long long *n, float *alpha, float *x, long long *incx, float *y, long long *incy, float *A, long long *lda); - -// level 3 -void sgemm_(char *ta, char *tb, long long *m, long long *n, long long *k, float *alpha, float *A, long long *lda, float *B, long long *ldb, float *beta, float *C, long long *ldc); -void ssyrk_(char *uplo, char *trans, long long *n, long long *k, float *alpha, float *A, long long *lda, float *beta, float *C, long long *ldc); -void strmm_(char *side, char *uplo, char *transa, char *diag, long long *m, long long *n, float *alpha, float *A, long long *lda, float *B, long long *ldb); -void strsm_(char *side, char *uplo, char *transa, char *diag, long long *m, long long *n, float *alpha, float *A, long long *lda, float *B, long long *ldb); - -// lapack -void spotrf_(char *uplo, long long *m, float *A, long long *lda, long long *info); -void sgetrf_(long long *m, long long *n, float *A, long long *lda, long long *ipiv, long long *info); -void sgeqrf_(long long *m, long long *n, float *A, long long *lda, float *tau, float *work, long long *lwork, long long *info); -void sgeqr2_(long long *m, long long *n, float *A, long long *lda, float *tau, float *work, long long *info); - - - -#ifdef __cplusplus -} -#endif diff --git a/third_party/acados/include/hpipm/include/hpipm_aux_mem.h b/third_party/acados/include/hpipm/include/hpipm_aux_mem.h deleted file mode 100644 index 7bd3d7e8bc..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_aux_mem.h +++ /dev/null @@ -1,52 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_AUX_MEM_H_ -#define HPIPM_AUX_MEM_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - -void hpipm_zero_memset(hpipm_size_t memsize, void *mem); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // HPIPM_AUX_MEM_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_aux_string.h b/third_party/acados/include/hpipm/include/hpipm_aux_string.h deleted file mode 100644 index 804cba5dc1..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_aux_string.h +++ /dev/null @@ -1,50 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_AUX_STRING_H_ -#define HPIPM_AUX_STRING_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#define MAX_STR_LEN 5 -int hpipm_strcmp(char *str1, char *str2); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // HPIPM_AUX_STRING_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_common.h b/third_party/acados/include/hpipm/include/hpipm_common.h deleted file mode 100644 index 0cc96a7b50..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_common.h +++ /dev/null @@ -1,76 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_COMMON_H_ -#define HPIPM_COMMON_H_ - -#include - -#ifdef __cplusplus -extern "C" { -#endif - -typedef size_t hpipm_size_t; - -enum hpipm_mode - { - SPEED_ABS, // focus on speed, absolute IPM formulation - SPEED, // focus on speed, relative IPM formulation - BALANCE, // balanced mode, relative IPM formulation - ROBUST, // focus on robustness, relative IPM formulation - }; - -enum hpipm_status - { - SUCCESS, // found solution satisfying accuracy tolerance - MAX_ITER, // maximum iteration number reached - MIN_STEP, // minimum step length reached - NAN_SOL, // NaN in solution detected - INCONS_EQ, // unconsistent equality constraints - }; - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_COMMON_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_cast_qcqp.h b/third_party/acados/include/hpipm/include/hpipm_d_cast_qcqp.h deleted file mode 100644 index 0e4c41f221..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_cast_qcqp.h +++ /dev/null @@ -1,71 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_D_CAST_QCQP_H_ -#define HPIPM_D_CAST_QCQP_H_ - - - -#include -#include - -#include "hpipm_d_dense_qcqp.h" -#include "hpipm_d_dense_qcqp_sol.h" -#include "hpipm_d_ocp_qcqp.h" -#include "hpipm_d_ocp_qcqp_dim.h" -#include "hpipm_d_ocp_qcqp_sol.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void d_cast_qcqp_compute_dim(struct d_ocp_qcqp_dim *ocp_dim, struct d_dense_qcqp_dim *dense_dim); -// -void d_cast_qcqp_cond(struct d_ocp_qcqp *ocp_qp, struct d_dense_qcqp *dense_qp); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_CAST_QCQP_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_cond.h b/third_party/acados/include/hpipm/include/hpipm_d_cond.h deleted file mode 100644 index 5900a2ab10..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_cond.h +++ /dev/null @@ -1,135 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_D_COND_H_ -#define HPIPM_D_COND_H_ - - - -#include -#include - -#include "hpipm_d_dense_qp.h" -#include "hpipm_d_dense_qp_sol.h" -#include "hpipm_d_ocp_qp.h" -#include "hpipm_d_ocp_qp_dim.h" -#include "hpipm_d_ocp_qp_sol.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_cond_qp_arg - { - int cond_last_stage; // condense last stage - int cond_alg; // condensing algorithm: 0 N2-nx3, 1 N3-nx2 - int comp_prim_sol; // primal solution (v) - int comp_dual_sol_eq; // dual solution equality constr (pi) - int comp_dual_sol_ineq; // dual solution inequality constr (lam t) - int square_root_alg; // square root algorithm (faster but requires RSQ>0) - hpipm_size_t memsize; - }; - - - -struct d_cond_qp_ws - { - struct blasfeo_dmat *Gamma; - struct blasfeo_dmat *GammaQ; - struct blasfeo_dmat *L; - struct blasfeo_dmat *Lx; - struct blasfeo_dmat *AL; - struct blasfeo_dvec *Gammab; - struct blasfeo_dvec *l; - struct blasfeo_dvec *tmp_nbgM; - struct blasfeo_dvec *tmp_nuxM; - int bs; // block size - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_cond_qp_arg_memsize(); -// -void d_cond_qp_arg_create(struct d_cond_qp_arg *cond_arg, void *mem); -// -void d_cond_qp_arg_set_default(struct d_cond_qp_arg *cond_arg); -// condensing algorithm: 0 N2-nx3, 1 N3-nx2 -void d_cond_qp_arg_set_cond_alg(int cond_alg, struct d_cond_qp_arg *cond_arg); -// set riccati-like algorithm: 0 classical, 1 square-root -void d_cond_qp_arg_set_ric_alg(int ric_alg, struct d_cond_qp_arg *cond_arg); -// condense last stage: 0 last stage disregarded, 1 last stage condensed too -void d_cond_qp_arg_set_cond_last_stage(int cond_last_stage, struct d_cond_qp_arg *cond_arg); -// -void d_cond_qp_arg_set_comp_prim_sol(int value, struct d_cond_qp_arg *cond_arg); -// -void d_cond_qp_arg_set_comp_dual_sol_eq(int value, struct d_cond_qp_arg *cond_arg); -// -void d_cond_qp_arg_set_comp_dual_sol_ineq(int value, struct d_cond_qp_arg *cond_arg); - -// -void d_cond_qp_compute_dim(struct d_ocp_qp_dim *ocp_dim, struct d_dense_qp_dim *dense_dim); -// -hpipm_size_t d_cond_qp_ws_memsize(struct d_ocp_qp_dim *ocp_dim, struct d_cond_qp_arg *cond_arg); -// -void d_cond_qp_ws_create(struct d_ocp_qp_dim *ocp_dim, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws, void *mem); -// -void d_cond_qp_cond(struct d_ocp_qp *ocp_qp, struct d_dense_qp *dense_qp, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_cond_qp_cond_lhs(struct d_ocp_qp *ocp_qp, struct d_dense_qp *dense_qp, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_cond_qp_cond_rhs(struct d_ocp_qp *ocp_qp, struct d_dense_qp *dense_qp, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_cond_qp_expand_sol(struct d_ocp_qp *ocp_qp, struct d_dense_qp_sol *dense_qp_sol, struct d_ocp_qp_sol *ocp_qp_sol, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// TODO remove -void d_cond_qp_expand_primal_sol(struct d_ocp_qp *ocp_qp, struct d_dense_qp_sol *dense_qp_sol, struct d_ocp_qp_sol *ocp_qp_sol, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); - -// -void d_cond_qp_update(int *idxc, struct d_ocp_qp *ocp_qp, struct d_dense_qp *dense_qp, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_COND_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_cond_aux.h b/third_party/acados/include/hpipm/include/hpipm_d_cond_aux.h deleted file mode 100644 index 73afba3c7e..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_cond_aux.h +++ /dev/null @@ -1,92 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_D_COND_AUX_H_ -#define HPIPM_D_COND_AUX_H_ - - - -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void d_cond_BAbt(struct d_ocp_qp *ocp_qp, struct blasfeo_dmat *BAbt2, struct blasfeo_dvec *b, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_cond_BAt(struct d_ocp_qp *ocp_qp, struct blasfeo_dmat *BAbt2, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_cond_b(struct d_ocp_qp *ocp_qp, struct blasfeo_dvec *b, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_cond_RSQrq(struct d_ocp_qp *ocp_qp, struct blasfeo_dmat *RSQrq2, struct blasfeo_dvec *rq, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_cond_RSQ(struct d_ocp_qp *ocp_qp, struct blasfeo_dmat *RSQrq2, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_cond_rq(struct d_ocp_qp *ocp_qp, struct blasfeo_dvec *rq, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_cond_DCtd(struct d_ocp_qp *ocp_qp, int *idxb2, struct blasfeo_dmat *DCt2, struct blasfeo_dvec *d2, struct blasfeo_dvec *d_mask2, int *idxs_rev2, struct blasfeo_dvec *Z2, struct blasfeo_dvec *z, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_cond_DCt(struct d_ocp_qp *ocp_qp, int *idxb2, struct blasfeo_dmat *DCt2, int *idxs_rev2, struct blasfeo_dvec *Z2, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_cond_d(struct d_ocp_qp *ocp_qp, struct blasfeo_dvec *d2, struct blasfeo_dvec *d_mask2, struct blasfeo_dvec *z, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_expand_sol(struct d_ocp_qp *ocp_qp, struct d_dense_qp_sol *dense_qp_sol, struct d_ocp_qp_sol *ocp_qp_so, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_expand_primal_sol(struct d_ocp_qp *ocp_qp, struct d_dense_qp_sol *dense_qp_sol, struct d_ocp_qp_sol *ocp_qp_so, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); - -// -void d_update_cond_BAbt(int *idxc, struct d_ocp_qp *ocp_qp, struct blasfeo_dmat *BAbt2, struct blasfeo_dvec *b, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_update_cond_RSQrq_N2nx3(int *idxc, struct d_ocp_qp *ocp_qp, struct blasfeo_dmat *RSQrq2, struct blasfeo_dvec *rq, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_update_cond_DCtd(int *idxc, struct d_ocp_qp *ocp_qp, int *idxb2, struct blasfeo_dmat *DCt2, struct blasfeo_dvec *d2, int *idxs2, struct blasfeo_dvec *Z2, struct blasfeo_dvec *z, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_COND_AUX_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_cond_qcqp.h b/third_party/acados/include/hpipm/include/hpipm_d_cond_qcqp.h deleted file mode 100644 index 266567bb8d..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_cond_qcqp.h +++ /dev/null @@ -1,129 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_D_COND_QCQP_H_ -#define HPIPM_D_COND_QCQP_H_ - - - -#include -#include - -#include "hpipm_d_dense_qcqp.h" -#include "hpipm_d_dense_qcqp_sol.h" -#include "hpipm_d_ocp_qcqp.h" -#include "hpipm_d_ocp_qcqp_dim.h" -#include "hpipm_d_ocp_qcqp_sol.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_cond_qcqp_arg - { - struct d_cond_qp_arg *qp_arg; - int cond_last_stage; // condense last stage -// int cond_variant; // TODO - int comp_prim_sol; // primal solution (v) - int comp_dual_sol_eq; // dual solution equality constr (pi) - int comp_dual_sol_ineq; // dual solution equality constr (lam t) - int square_root_alg; // square root algorithm (faster but requires RSQ>0) - hpipm_size_t memsize; - }; - - - -struct d_cond_qcqp_ws - { - struct d_cond_qp_ws *qp_ws; - struct blasfeo_dmat *hess_array; // TODO remove - struct blasfeo_dmat *zero_hess; // TODO remove - struct blasfeo_dvec *grad_array; // TODO remove - struct blasfeo_dvec *zero_grad; // TODO remove - struct blasfeo_dvec *tmp_nvc; - struct blasfeo_dvec *tmp_nuxM; - struct blasfeo_dmat *GammaQ; - struct blasfeo_dmat *tmp_DCt; - struct blasfeo_dmat *tmp_nuM_nxM; -// struct blasfeo_dvec *d_qp; -// struct blasfeo_dvec *d_mask_qp; - hpipm_size_t memsize; - }; - - -// -hpipm_size_t d_cond_qcqp_arg_memsize(); -// -void d_cond_qcqp_arg_create(struct d_cond_qcqp_arg *cond_arg, void *mem); -// -void d_cond_qcqp_arg_set_default(struct d_cond_qcqp_arg *cond_arg); -// set riccati-like algorithm: 0 classical, 1 square-root -void d_cond_qcqp_arg_set_ric_alg(int ric_alg, struct d_cond_qcqp_arg *cond_arg); -// condense last stage: 0 last stage disregarded, 1 last stage condensed too -void d_cond_qcqp_arg_set_cond_last_stage(int cond_last_stage, struct d_cond_qcqp_arg *cond_arg); - -// -void d_cond_qcqp_compute_dim(struct d_ocp_qcqp_dim *ocp_dim, struct d_dense_qcqp_dim *dense_dim); -// -hpipm_size_t d_cond_qcqp_ws_memsize(struct d_ocp_qcqp_dim *ocp_dim, struct d_cond_qcqp_arg *cond_arg); -// -void d_cond_qcqp_ws_create(struct d_ocp_qcqp_dim *ocp_dim, struct d_cond_qcqp_arg *cond_arg, struct d_cond_qcqp_ws *cond_ws, void *mem); -// -void d_cond_qcqp_qc(struct d_ocp_qcqp *ocp_qp, struct blasfeo_dmat *Hq2, int *Hq_nzero2, struct blasfeo_dmat *Ct2, struct blasfeo_dvec *d2, struct d_cond_qcqp_arg *cond_arg, struct d_cond_qcqp_ws *cond_ws); -// -void d_cond_qcqp_qc_lhs(struct d_ocp_qcqp *ocp_qp, struct blasfeo_dmat *Hq2, int *Hq_nzero2, struct blasfeo_dmat *Ct2, struct d_cond_qcqp_arg *cond_arg, struct d_cond_qcqp_ws *cond_ws); -// -void d_cond_qcqp_qc_rhs(struct d_ocp_qcqp *ocp_qp, struct blasfeo_dvec *d2, struct d_cond_qcqp_arg *cond_arg, struct d_cond_qcqp_ws *cond_ws); -// -void d_cond_qcqp_cond(struct d_ocp_qcqp *ocp_qp, struct d_dense_qcqp *dense_qp, struct d_cond_qcqp_arg *cond_arg, struct d_cond_qcqp_ws *cond_ws); -// -void d_cond_qcqp_cond_rhs(struct d_ocp_qcqp *ocp_qp, struct d_dense_qcqp *dense_qp, struct d_cond_qcqp_arg *cond_arg, struct d_cond_qcqp_ws *cond_ws); -// -void d_cond_qcqp_cond_lhs(struct d_ocp_qcqp *ocp_qp, struct d_dense_qcqp *dense_qp, struct d_cond_qcqp_arg *cond_arg, struct d_cond_qcqp_ws *cond_ws); -// -void d_cond_qcqp_expand_sol(struct d_ocp_qcqp *ocp_qp, struct d_dense_qcqp_sol *dense_qp_sol, struct d_ocp_qcqp_sol *ocp_qp_sol, struct d_cond_qcqp_arg *cond_arg, struct d_cond_qcqp_ws *cond_ws); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_COND_QCQP_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_core_qp_ipm.h b/third_party/acados/include/hpipm/include/hpipm_d_core_qp_ipm.h deleted file mode 100644 index f39d9a9b50..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_core_qp_ipm.h +++ /dev/null @@ -1,101 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_CORE_QP_IPM_ -#define HPIPM_D_CORE_QP_IPM_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - -struct d_core_qp_ipm_workspace - { - double *v; // primal variables - double *pi; // equality constraints multipliers - double *lam; // inequality constraints multipliers - double *t; // inequality constraints slacks - double *t_inv; // inverse of t - double *v_bkp; // backup of primal variables - double *pi_bkp; // backup of equality constraints multipliers - double *lam_bkp; // backup of inequality constraints multipliers - double *t_bkp; // backup of inequality constraints slacks - double *dv; // step in v - double *dpi; // step in pi - double *dlam; // step in lam - double *dt; // step in t - double *res_g; // q-residuals - double *res_b; // b-residuals - double *res_d; // d-residuals - double *res_m; // m-residuals - double *res_m_bkp; // m-residuals - double *Gamma; // Hessian update - double *gamma; // gradient update - double alpha; // step length - double alpha_prim; // step length - double alpha_dual; // step length - double sigma; // centering XXX - double mu; // duality measuere - double mu_aff; // affine duality measuere - double nc_inv; // 1.0/nc, where nc is the total number of inequality constraints - double nc_mask_inv; // 1.0/nc_mask - double lam_min; // min value in lam vector - double t_min; // min value in t vector - double t_min_inv; // inverse of min value in t vector - double tau_min; // min value of barrier parameter - int nv; // number of primal variables - int ne; // number of equality constraints - int nc; // (twice the) number of (two-sided) inequality constraints - int nc_mask; // total number of ineq constr after masking - int split_step; // use different step for primal and dual variables - int t_lam_min; // clip t and lam also in solution, or only in Gamma computation - hpipm_size_t memsize; // memory size (in bytes) of workspace - }; - - - -// -hpipm_size_t d_memsize_core_qp_ipm(int nv, int ne, int nc); -// -void d_create_core_qp_ipm(int nv, int ne, int nc, struct d_core_qp_ipm_workspace *workspace, void *mem); -// -void d_core_qp_ipm(struct d_core_qp_ipm_workspace *workspace); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // HPIPM_D_CORE_QP_IPM_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_core_qp_ipm_aux.h b/third_party/acados/include/hpipm/include/hpipm_d_core_qp_ipm_aux.h deleted file mode 100644 index 30cc824bad..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_core_qp_ipm_aux.h +++ /dev/null @@ -1,68 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_CORE_QP_IPM_AUX_ -#define HPIPM_S_CORE_QP_IPM_AUX_ - -#ifdef __cplusplus -extern "C" { -#endif - -// -void d_compute_Gamma_gamma_qp(double *res_d, double *res_m, struct d_core_qp_ipm_workspace *rws); -// -void d_compute_gamma_qp(double *res_d, double *res_m, struct d_core_qp_ipm_workspace *rws); -// -void d_compute_lam_t_qp(double *res_d, double *res_m, double *dlam, double *dt, struct d_core_qp_ipm_workspace *rws); -// -void d_compute_alpha_qp(struct d_core_qp_ipm_workspace *rws); -// -void d_update_var_qp(struct d_core_qp_ipm_workspace *rws); -// -void d_compute_mu_aff_qp(struct d_core_qp_ipm_workspace *rws); -// -void d_backup_res_m(struct d_core_qp_ipm_workspace *rws); -// -void d_compute_centering_correction_qp(struct d_core_qp_ipm_workspace *rws); -// -void d_compute_centering_qp(struct d_core_qp_ipm_workspace *rws); -// -void d_compute_tau_min_qp(struct d_core_qp_ipm_workspace *rws); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // HPIPM_S_CORE_QP_IPM_AUX_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp.h b/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp.h deleted file mode 100644 index 3da5716493..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp.h +++ /dev/null @@ -1,199 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_D_DENSE_QCQP_H_ -#define HPIPM_D_DENSE_QCQP_H_ - - - -#include -#include - -#include "hpipm_d_dense_qcqp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_dense_qcqp - { - struct d_dense_qcqp_dim *dim; - struct blasfeo_dmat *Hv; // hessian of cost & vector work space - struct blasfeo_dmat *A; // equality constraint matrix - struct blasfeo_dmat *Ct; // inequality constraints matrix - struct blasfeo_dmat *Hq; // hessians of quadratic constraints - struct blasfeo_dvec *gz; // gradient of cost & gradient of slacks - struct blasfeo_dvec *b; // equality constraint vector - struct blasfeo_dvec *d; // inequality constraints vector - struct blasfeo_dvec *d_mask; // inequality constraints mask vector - struct blasfeo_dvec *m; // rhs of complementarity condition - struct blasfeo_dvec *Z; // (diagonal) hessian of slacks - int *idxb; // indices of box constrained variables within [u; x] - int *idxs_rev; // index of soft constraints (reverse storage) - int *Hq_nzero; // for each int, the last 3 bits ...abc, {a,b,c}=0 => {R,S,Q}=0 - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t d_dense_qcqp_memsize(struct d_dense_qcqp_dim *dim); -// -void d_dense_qcqp_create(struct d_dense_qcqp_dim *dim, struct d_dense_qcqp *qp, void *memory); - -// -void d_dense_qcqp_set(char *field, void *value, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_H(double *H, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_g(double *g, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_A(double *A, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_b(double *b, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_idxb(int *idxb, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_lb(double *lb, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_lb_mask(double *lb, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_ub(double *ub, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_ub_mask(double *ub, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_C(double *C, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_lg(double *lg, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_lg_mask(double *lg, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_ug(double *ug, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_ug_mask(double *ug, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_Hq(double *Hq, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_gq(double *gq, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_uq(double *uq, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_uq_mask(double *uq, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_idxs(int *idxs, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_idxs_rev(int *idxs_rev, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_Zl(double *Zl, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_Zu(double *Zu, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_zl(double *zl, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_zu(double *zu, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_ls(double *ls, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_ls_mask(double *ls, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_us(double *us, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_us_mask(double *us, struct d_dense_qcqp *qp); - -// getters (COLMAJ) - -void d_dense_qcqp_get_H(struct d_dense_qcqp *qp, double *H); -// -void d_dense_qcqp_get_g(struct d_dense_qcqp *qp, double *g); -// -void d_dense_qcqp_get_A(struct d_dense_qcqp *qp, double *A); -// -void d_dense_qcqp_get_b(struct d_dense_qcqp *qp, double *b); -// -void d_dense_qcqp_get_idxb(struct d_dense_qcqp *qp, int *idxb); -// -void d_dense_qcqp_get_lb(struct d_dense_qcqp *qp, double *lb); -// -void d_dense_qcqp_get_lb_mask(struct d_dense_qcqp *qp, double *lb); -// -void d_dense_qcqp_get_ub(struct d_dense_qcqp *qp, double *ub); -// -void d_dense_qcqp_get_ub_mask(struct d_dense_qcqp *qp, double *ub); -// -void d_dense_qcqp_get_C(struct d_dense_qcqp *qp, double *C); -// -void d_dense_qcqp_get_lg(struct d_dense_qcqp *qp, double *lg); -// -void d_dense_qcqp_get_lg_mask(struct d_dense_qcqp *qp, double *lg); -// -void d_dense_qcqp_get_ug(struct d_dense_qcqp *qp, double *ug); -// -void d_dense_qcqp_get_ug_mask(struct d_dense_qcqp *qp, double *ug); -// -void d_dense_qcqp_get_idxs(struct d_dense_qcqp *qp, int *idxs); -// -void d_dense_qcqp_get_idxs_rev(struct d_dense_qcqp *qp, int *idxs_rev); -// -void d_dense_qcqp_get_Zl(struct d_dense_qcqp *qp, double *Zl); -// -void d_dense_qcqp_get_Zu(struct d_dense_qcqp *qp, double *Zu); -// -void d_dense_qcqp_get_zl(struct d_dense_qcqp *qp, double *zl); -// -void d_dense_qcqp_get_zu(struct d_dense_qcqp *qp, double *zu); -// -void d_dense_qcqp_get_ls(struct d_dense_qcqp *qp, double *ls); -// -void d_dense_qcqp_get_ls_mask(struct d_dense_qcqp *qp, double *ls); -// -void d_dense_qcqp_get_us(struct d_dense_qcqp *qp, double *us); -// -void d_dense_qcqp_get_us_mask(struct d_dense_qcqp *qp, double *us); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_DENSE_QCQP_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_dim.h b/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_dim.h deleted file mode 100644 index fa8c574a1e..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_dim.h +++ /dev/null @@ -1,98 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_DENSE_QCQP_DIM_H_ -#define HPIPM_D_DENSE_QCQP_DIM_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_dense_qcqp_dim - { - struct d_dense_qp_dim *qp_dim; // dim of qp approximation - int nv; // number of variables - int ne; // number of equality constraints - int nb; // number of box constraints - int ng; // number of general constraints - int nq; // number of quadratic constraints - int nsb; // number of softened box constraints - int nsg; // number of softened general constraints - int nsq; // number of softened quadratic constraints - int ns; // number of softened constraints (nsb+nsg+nsq) TODO number of slacks - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_dense_qcqp_dim_memsize(); -// -void d_dense_qcqp_dim_create(struct d_dense_qcqp_dim *dim, void *memory); -// -void d_dense_qcqp_dim_set(char *field_name, int value, struct d_dense_qcqp_dim *dim); -// -void d_dense_qcqp_dim_set_nv(int value, struct d_dense_qcqp_dim *dim); -// -void d_dense_qcqp_dim_set_ne(int value, struct d_dense_qcqp_dim *dim); -// -void d_dense_qcqp_dim_set_nb(int value, struct d_dense_qcqp_dim *dim); -// -void d_dense_qcqp_dim_set_ng(int value, struct d_dense_qcqp_dim *dim); -// -void d_dense_qcqp_dim_set_nq(int value, struct d_dense_qcqp_dim *dim); -// -void d_dense_qcqp_dim_set_nsb(int value, struct d_dense_qcqp_dim *dim); -// -void d_dense_qcqp_dim_set_nsg(int value, struct d_dense_qcqp_dim *dim); -// -void d_dense_qcqp_dim_set_nsq(int value, struct d_dense_qcqp_dim *dim); -// -void d_dense_qcqp_dim_set_ns(int value, struct d_dense_qcqp_dim *dim); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_DENSE_QCQP_DIM_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_ipm.h b/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_ipm.h deleted file mode 100644 index fa3f98fa79..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_ipm.h +++ /dev/null @@ -1,193 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_D_DENSE_QCQP_IPM_H_ -#define HPIPM_D_DENSE_QCQP_IPM_H_ - - - -#include -#include - -#include -#include -#include -#include -#include - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_dense_qcqp_ipm_arg - { - struct d_dense_qp_ipm_arg *qp_arg; - double mu0; // initial value for duality measure - double alpha_min; // exit cond on step length - double res_g_max; // exit cond on inf norm of residuals - double res_b_max; // exit cond on inf norm of residuals - double res_d_max; // exit cond on inf norm of residuals - double res_m_max; // exit cond on inf norm of residuals - double reg_prim; // reg of primal hessian - double reg_dual; // reg of dual hessian - double lam_min; // min value in lam vector - double t_min; // min value in t vector - int iter_max; // exit cond in iter number - int stat_max; // iterations saved in stat - int pred_corr; // Mehrotra's predictor-corrector IPM algirthm - int cond_pred_corr; // conditional Mehrotra's predictor-corrector - int scale; // scale hessian - int itref_pred_max; // max number of iterative refinement steps for predictor step - int itref_corr_max; // max number of iterative refinement steps for corrector step - int warm_start; // 0 no warm start, 1 warm start primal sol, 2 warm start primal and dual sol - int lq_fact; // 0 syrk+potrf, 1 mix, 2 lq - int abs_form; // absolute IPM formulation - int comp_res_exit; // compute residuals on exit (only for abs_form==1) - int comp_res_pred; // compute residuals of prediction - int split_step; // use different step for primal and dual variables - int t_lam_min; // clip t and lam: 0 no, 1 in Gamma computation, 2 in solution - int mode; - hpipm_size_t memsize; - }; - - - -struct d_dense_qcqp_ipm_ws - { - struct d_dense_qp_ipm_ws *qp_ws; - struct d_dense_qp *qp; - struct d_dense_qp_sol *qp_sol; - struct d_dense_qcqp_res_ws *qcqp_res_ws; - struct d_dense_qcqp_res *qcqp_res; - struct blasfeo_dvec *tmp_nv; - int iter; // iteration number - int status; - hpipm_size_t memsize; // memory size (in bytes) of workspace - }; - - - -// -hpipm_size_t d_dense_qcqp_ipm_arg_memsize(struct d_dense_qcqp_dim *dim); -// -void d_dense_qcqp_ipm_arg_create(struct d_dense_qcqp_dim *dim, struct d_dense_qcqp_ipm_arg *arg, void *mem); -// -void d_dense_qcqp_ipm_arg_set_default(enum hpipm_mode mode, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set(char *field, void *value, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_iter_max(int *iter_max, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_alpha_min(double *alpha_min, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_mu0(double *mu0, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_tol_stat(double *tol_stat, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_tol_eq(double *tol_eq, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_tol_ineq(double *tol_ineq, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_tol_comp(double *tol_comp, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_reg_prim(double *reg, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_reg_dual(double *reg, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_warm_start(int *warm_start, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_pred_corr(int *pred_corr, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_cond_pred_corr(int *cond_pred_corr, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_comp_res_pred(int *comp_res_pred, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_comp_res_exit(int *comp_res_exit, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_lam_min(double *value, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_t_min(double *value, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_split_step(int *value, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_t_lam_min(int *value, struct d_dense_qcqp_ipm_arg *arg); - -// -hpipm_size_t d_dense_qcqp_ipm_ws_memsize(struct d_dense_qcqp_dim *qp_dim, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_ws_create(struct d_dense_qcqp_dim *qp_dim, struct d_dense_qcqp_ipm_arg *arg, struct d_dense_qcqp_ipm_ws *ws, void *mem); -// -void d_dense_qcqp_ipm_get(char *field, struct d_dense_qcqp_ipm_ws *ws, void *value); -// -void d_dense_qcqp_ipm_get_status(struct d_dense_qcqp_ipm_ws *ws, int *status); -// -void d_dense_qcqp_ipm_get_iter(struct d_dense_qcqp_ipm_ws *ws, int *iter); -// -void d_dense_qcqp_ipm_get_max_res_stat(struct d_dense_qcqp_ipm_ws *ws, double *res_stat); -// -void d_dense_qcqp_ipm_get_max_res_eq(struct d_dense_qcqp_ipm_ws *ws, double *res_eq); -// -void d_dense_qcqp_ipm_get_max_res_ineq(struct d_dense_qcqp_ipm_ws *ws, double *res_ineq); -// -void d_dense_qcqp_ipm_get_max_res_comp(struct d_dense_qcqp_ipm_ws *ws, double *res_comp); -// -void d_dense_qcqp_ipm_get_stat(struct d_dense_qcqp_ipm_ws *ws, double **stat); -// -void d_dense_qcqp_ipm_get_stat_m(struct d_dense_qcqp_ipm_ws *ws, int *stat_m); -// -void d_dense_qcqp_init_var(struct d_dense_qcqp *qp, struct d_dense_qcqp_sol *qp_sol, struct d_dense_qcqp_ipm_arg *arg, struct d_dense_qcqp_ipm_ws *ws); -// -void d_dense_qcqp_ipm_solve(struct d_dense_qcqp *qp, struct d_dense_qcqp_sol *qp_sol, struct d_dense_qcqp_ipm_arg *arg, struct d_dense_qcqp_ipm_ws *ws); -#if 0 -// -void d_dense_qcqp_ipm_predict(struct d_dense_qcqp *qp, struct d_dense_qcqp_sol *qp_sol, struct d_dense_qcqp_ipm_arg *arg, struct d_dense_qcqp_ipm_ws *ws); -// -void d_dense_qcqp_ipm_sens(struct d_dense_qcqp *qp, struct d_dense_qcqp_sol *qp_sol, struct d_dense_qcqp_ipm_arg *arg, struct d_dense_qcqp_ipm_ws *ws); -#endif - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_DENSE_QCQP_IPM_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_res.h b/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_res.h deleted file mode 100644 index a76f16215e..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_res.h +++ /dev/null @@ -1,107 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_DENSE_QCQP_RES_H_ -#define HPIPM_D_DENSE_QCQP_RES_H_ - - - -#include -#include - -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_dense_qcqp_res - { - struct d_dense_qcqp_dim *dim; - struct blasfeo_dvec *res_g; // q-residuals - struct blasfeo_dvec *res_b; // b-residuals - struct blasfeo_dvec *res_d; // d-residuals - struct blasfeo_dvec *res_m; // m-residuals - double res_max[4]; // infinity norm of residuals - double res_mu; // mu-residual - hpipm_size_t memsize; - }; - - - -struct d_dense_qcqp_res_ws - { - struct blasfeo_dvec *tmp_nv; // work space of size nv - struct blasfeo_dvec *tmp_nbgq; // work space of size nbM+ngM+nqM - struct blasfeo_dvec *tmp_ns; // work space of size nsM - struct blasfeo_dvec *q_fun; // value for evaluation of quadr constr - struct blasfeo_dvec *q_adj; // value for adjoint of quadr constr - int use_q_fun; // reuse cached value for evaluation of quadr constr - int use_q_adj; // reuse cached value for adjoint of quadr constr - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_dense_qcqp_res_memsize(struct d_dense_qcqp_dim *dim); -// -void d_dense_qcqp_res_create(struct d_dense_qcqp_dim *dim, struct d_dense_qcqp_res *res, void *mem); -// -hpipm_size_t d_dense_qcqp_res_ws_memsize(struct d_dense_qcqp_dim *dim); -// -void d_dense_qcqp_res_ws_create(struct d_dense_qcqp_dim *dim, struct d_dense_qcqp_res_ws *workspace, void *mem); -// -void d_dense_qcqp_res_compute(struct d_dense_qcqp *qp, struct d_dense_qcqp_sol *qp_sol, struct d_dense_qcqp_res *res, struct d_dense_qcqp_res_ws *ws); -// -void d_dense_qcqp_res_compute_inf_norm(struct d_dense_qcqp_res *res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_D_DENSE_QCQP_RES_H_ - - - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_sol.h b/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_sol.h deleted file mode 100644 index 6c697a8e69..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_sol.h +++ /dev/null @@ -1,85 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_D_DENSE_QCQP_SOL_H_ -#define HPIPM_D_DENSE_QCQP_SOL_H_ - - - -#include -#include - -#include "hpipm_d_dense_qcqp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_dense_qcqp_sol - { - struct d_dense_qcqp_dim *dim; - struct blasfeo_dvec *v; - struct blasfeo_dvec *pi; - struct blasfeo_dvec *lam; - struct blasfeo_dvec *t; - void *misc; - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_dense_qcqp_sol_memsize(struct d_dense_qcqp_dim *dim); -// -void d_dense_qcqp_sol_create(struct d_dense_qcqp_dim *dim, struct d_dense_qcqp_sol *qp_sol, void *memory); -// -void d_dense_qcqp_sol_get_v(struct d_dense_qcqp_sol *qp_sol, double *v); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_DENSE_QCQP_SOL_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_utils.h b/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_utils.h deleted file mode 100644 index a34218bae4..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_utils.h +++ /dev/null @@ -1,82 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_DENSE_QCQP_UTILS_H_ -#define HPIPM_D_DENSE_QCQP_UTILS_H_ - - - -#include -#include - -#include "hpipm_d_dense_qcqp_dim.h" -#include "hpipm_d_dense_qcqp.h" -#include "hpipm_d_dense_qcqp_sol.h" -//#include "hpipm_d_dense_qcqp_ipm.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void d_dense_qcqp_dim_print(struct d_dense_qcqp_dim *qp_dim); -// -//void d_dense_qcqp_dim_codegen(char *file_name, char *mode, struct d_dense_qcqp_dim *qp_dim); -// -void d_dense_qcqp_print(struct d_dense_qcqp_dim *qp_dim, struct d_dense_qcqp *qp); -// -//void d_dense_qcqp_codegen(char *file_name, char *mode, struct d_dense_qcqp_dim *qp_dim, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_sol_print(struct d_dense_qcqp_dim *qp_dim, struct d_dense_qcqp_sol *dense_qcqp_sol); -// -//void d_dense_qcqp_ipm_arg_codegen(char *file_name, char *mode, struct d_dense_qcqp_dim *qp_dim, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_res_print(struct d_dense_qcqp_dim *qp_dim, struct d_dense_qcqp_res *dense_qcqp_res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_DENSE_QCQP_UTILS_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_dense_qp.h b/third_party/acados/include/hpipm/include/hpipm_d_dense_qp.h deleted file mode 100644 index 02fba5a922..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_dense_qp.h +++ /dev/null @@ -1,207 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_D_DENSE_QP_H_ -#define HPIPM_D_DENSE_QP_H_ - - - -#include -#include - -#include "hpipm_d_dense_qp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_dense_qp - { - struct d_dense_qp_dim *dim; - struct blasfeo_dmat *Hv; // hessian of cost & vector work space - struct blasfeo_dmat *A; // equality constraint matrix - struct blasfeo_dmat *Ct; // inequality constraints matrix - struct blasfeo_dvec *gz; // gradient of cost & gradient of slacks - struct blasfeo_dvec *b; // equality constraint vector - struct blasfeo_dvec *d; // inequality constraints vector - struct blasfeo_dvec *d_mask; // inequality constraints mask vector - struct blasfeo_dvec *m; // rhs of complementarity condition - struct blasfeo_dvec *Z; // (diagonal) hessian of slacks - int *idxb; // indices of box constrained variables within [u; x] - int *idxs_rev; // index of soft constraints (reverse storage) - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t d_dense_qp_memsize(struct d_dense_qp_dim *dim); -// -void d_dense_qp_create(struct d_dense_qp_dim *dim, struct d_dense_qp *qp, void *memory); - -// setters - colmaj -// -void d_dense_qp_set_all(double *H, double *g, double *A, double *b, int *idxb, double *d_lb, double *d_ub, double *C, double *d_lg, double *d_ug, double *Zl, double *Zu, double *zl, double *zu, int *idxs, double *d_ls, double *d_us, struct d_dense_qp *qp); -// -void d_dense_qp_get_all(struct d_dense_qp *qp, double *H, double *g, double *A, double *b, int *idxb, double *d_lb, double *d_ub, double *C, double *d_lg, double *d_ug, double *Zl, double *Zu, double *zl, double *zu, int *idxs, double *d_ls, double *d_us); -// -void d_dense_qp_set(char *field, void *value, struct d_dense_qp *qp); -// -void d_dense_qp_set_H(double *H, struct d_dense_qp *qp); -// -void d_dense_qp_set_g(double *g, struct d_dense_qp *qp); -// -void d_dense_qp_set_A(double *A, struct d_dense_qp *qp); -// -void d_dense_qp_set_b(double *b, struct d_dense_qp *qp); -// -void d_dense_qp_set_idxb(int *idxb, struct d_dense_qp *qp); -// -void d_dense_qp_set_Jb(double *Jb, struct d_dense_qp *qp); -// -void d_dense_qp_set_lb(double *lb, struct d_dense_qp *qp); -// -void d_dense_qp_set_lb_mask(double *lb, struct d_dense_qp *qp); -// -void d_dense_qp_set_ub(double *ub, struct d_dense_qp *qp); -// -void d_dense_qp_set_ub_mask(double *ub, struct d_dense_qp *qp); -// -void d_dense_qp_set_C(double *C, struct d_dense_qp *qp); -// -void d_dense_qp_set_lg(double *lg, struct d_dense_qp *qp); -// -void d_dense_qp_set_lg_mask(double *lg, struct d_dense_qp *qp); -// -void d_dense_qp_set_ug(double *ug, struct d_dense_qp *qp); -// -void d_dense_qp_set_ug_mask(double *ug, struct d_dense_qp *qp); -// -void d_dense_qp_set_idxs(int *idxs, struct d_dense_qp *qp); -// -void d_dense_qp_set_idxs_rev(int *idxs_rev, struct d_dense_qp *qp); -// -void d_dense_qp_set_Jsb(double *Jsb, struct d_dense_qp *qp); -// -void d_dense_qp_set_Jsg(double *Jsg, struct d_dense_qp *qp); -// -void d_dense_qp_set_Zl(double *Zl, struct d_dense_qp *qp); -// -void d_dense_qp_set_Zu(double *Zu, struct d_dense_qp *qp); -// -void d_dense_qp_set_zl(double *zl, struct d_dense_qp *qp); -// -void d_dense_qp_set_zu(double *zu, struct d_dense_qp *qp); -// -void d_dense_qp_set_ls(double *ls, struct d_dense_qp *qp); -// -void d_dense_qp_set_ls_mask(double *ls, struct d_dense_qp *qp); -// -void d_dense_qp_set_us(double *us, struct d_dense_qp *qp); -// -void d_dense_qp_set_us_mask(double *us, struct d_dense_qp *qp); - -// getters - colmaj -// -void d_dense_qp_get_H(struct d_dense_qp *qp, double *H); -// -void d_dense_qp_get_g(struct d_dense_qp *qp, double *g); -// -void d_dense_qp_get_A(struct d_dense_qp *qp, double *A); -// -void d_dense_qp_get_b(struct d_dense_qp *qp, double *b); -// -void d_dense_qp_get_idxb(struct d_dense_qp *qp, int *idxb); -// -void d_dense_qp_get_lb(struct d_dense_qp *qp, double *lb); -// -void d_dense_qp_get_lb_mask(struct d_dense_qp *qp, double *lb); -// -void d_dense_qp_get_ub(struct d_dense_qp *qp, double *ub); -// -void d_dense_qp_get_ub_mask(struct d_dense_qp *qp, double *ub); -// -void d_dense_qp_get_C(struct d_dense_qp *qp, double *C); -// -void d_dense_qp_get_lg(struct d_dense_qp *qp, double *lg); -// -void d_dense_qp_get_lg_mask(struct d_dense_qp *qp, double *lg); -// -void d_dense_qp_get_ug(struct d_dense_qp *qp, double *ug); -// -void d_dense_qp_get_ug_mask(struct d_dense_qp *qp, double *ug); -// -void d_dense_qp_get_idxs(struct d_dense_qp *qp, int *idxs); -// -void d_dense_qp_get_idxs_rev(struct d_dense_qp *qp, int *idxs_rev); -// -void d_dense_qp_get_Zl(struct d_dense_qp *qp, double *Zl); -// -void d_dense_qp_get_Zu(struct d_dense_qp *qp, double *Zu); -// -void d_dense_qp_get_zl(struct d_dense_qp *qp, double *zl); -// -void d_dense_qp_get_zu(struct d_dense_qp *qp, double *zu); -// -void d_dense_qp_get_ls(struct d_dense_qp *qp, double *ls); -// -void d_dense_qp_get_ls_mask(struct d_dense_qp *qp, double *ls); -// -void d_dense_qp_get_us(struct d_dense_qp *qp, double *us); -// -void d_dense_qp_get_us_mask(struct d_dense_qp *qp, double *us); - -// setters - rowmaj -// -void d_dense_qp_set_all_rowmaj(double *H, double *g, double *A, double *b, int *idxb, double *d_lb, double *d_ub, double *C, double *d_lg, double *d_ug, double *Zl, double *Zu, double *zl, double *zu, int *idxs, double *d_ls, double *d_us, struct d_dense_qp *qp); - -// getters - rowmaj -// -void d_dense_qp_get_all_rowmaj(struct d_dense_qp *qp, double *H, double *g, double *A, double *b, int *idxb, double *d_lb, double *d_ub, double *C, double *d_lg, double *d_ug, double *Zl, double *Zu, double *zl, double *zu, int *idxs, double *d_ls, double *d_us); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_DENSE_QP_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_dim.h b/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_dim.h deleted file mode 100644 index 98a551f312..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_dim.h +++ /dev/null @@ -1,92 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_DENSE_QP_DIM_H_ -#define HPIPM_D_DENSE_QP_DIM_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_dense_qp_dim - { - int nv; // number of variables - int ne; // number of equality constraints - int nb; // number of box constraints - int ng; // number of general constraints - int nsb; // number of softened box constraints - int nsg; // number of softened general constraints - int ns; // number of softened constraints (nsb+nsg) - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_dense_qp_dim_memsize(); -// -void d_dense_qp_dim_create(struct d_dense_qp_dim *qp_dim, void *memory); -// -void d_dense_qp_dim_set_all(int nv, int ne, int nb, int ng, int nsb, int nsg, struct d_dense_qp_dim *dim); -// -void d_dense_qp_dim_set(char *field_name, int value, struct d_dense_qp_dim *dim); -// -void d_dense_qp_dim_set_nv(int value, struct d_dense_qp_dim *dim); -// -void d_dense_qp_dim_set_ne(int value, struct d_dense_qp_dim *dim); -// -void d_dense_qp_dim_set_nb(int value, struct d_dense_qp_dim *dim); -// -void d_dense_qp_dim_set_ng(int value, struct d_dense_qp_dim *dim); -// -void d_dense_qp_dim_set_nsb(int value, struct d_dense_qp_dim *dim); -// -void d_dense_qp_dim_set_nsg(int value, struct d_dense_qp_dim *dim); -// -void d_dense_qp_dim_set_ns(int value, struct d_dense_qp_dim *dim); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_DENSE_QP_DIM_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_ipm.h b/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_ipm.h deleted file mode 100644 index e6e5d5d9b5..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_ipm.h +++ /dev/null @@ -1,260 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_D_DENSE_QP_IPM_H_ -#define HPIPM_D_DENSE_QP_IPM_H_ - - - -#include -#include - -#include -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_dense_qp_ipm_arg - { - double mu0; // initial value for duality measure - double alpha_min; // exit cond on step length - double res_g_max; // exit cond on inf norm of residuals - double res_b_max; // exit cond on inf norm of residuals - double res_d_max; // exit cond on inf norm of residuals - double res_m_max; // exit cond on inf norm of residuals - double reg_prim; // reg of primal hessian - double reg_dual; // reg of dual hessian - double lam_min; // min value in lam vector - double t_min; // min value in t vector - double tau_min; // min value of barrier parameter - int iter_max; // exit cond in iter number - int stat_max; // iterations saved in stat - int pred_corr; // Mehrotra's predictor-corrector IPM algirthm - int cond_pred_corr; // conditional Mehrotra's predictor-corrector - int scale; // scale hessian - int itref_pred_max; // max number of iterative refinement steps for predictor step - int itref_corr_max; // max number of iterative refinement steps for corrector step - int warm_start; // 0 no warm start, 1 warm start primal sol, 2 warm start primal and dual sol - int lq_fact; // 0 syrk+potrf, 1 mix, 2 lq - int abs_form; // absolute IPM formulation - int comp_res_exit; // compute residuals on exit (only for abs_form==1) - int comp_res_pred; // compute residuals of prediction - int kkt_fact_alg; // 0 null-space, 1 schur-complement - int remove_lin_dep_eq; // 0 do not, 1 do check and remove linearly dependent equality constraints - int compute_obj; // compute obj on exit - int split_step; // use different steps for primal and dual variables - int t_lam_min; // clip t and lam: 0 no, 1 in Gamma computation, 2 in solution - int mode; - hpipm_size_t memsize; - }; - - - -struct d_dense_qp_ipm_ws - { - struct d_core_qp_ipm_workspace *core_workspace; - struct d_dense_qp_res_ws *res_ws; - struct d_dense_qp_sol *sol_step; - struct d_dense_qp_sol *sol_itref; - struct d_dense_qp *qp_step; - struct d_dense_qp *qp_itref; - struct d_dense_qp_res *res; - struct d_dense_qp_res *res_itref; - struct d_dense_qp_res *res_step; - struct blasfeo_dvec *Gamma; // - struct blasfeo_dvec *gamma; // - struct blasfeo_dvec *Zs_inv; // - struct blasfeo_dmat *Lv; // - struct blasfeo_dmat *AL; // - struct blasfeo_dmat *Le; // - struct blasfeo_dmat *Ctx; // - struct blasfeo_dvec *lv; // - struct blasfeo_dvec *sv; // scale for Lv - struct blasfeo_dvec *se; // scale for Le - struct blasfeo_dvec *tmp_nbg; // work space of size nb+ng - struct blasfeo_dvec *tmp_ns; // work space of size ns - struct blasfeo_dmat *lq0; - struct blasfeo_dmat *lq1; - struct blasfeo_dvec *tmp_m; - struct blasfeo_dmat *A_LQ; - struct blasfeo_dmat *A_Q; - struct blasfeo_dmat *Zt; - struct blasfeo_dmat *ZtH; - struct blasfeo_dmat *ZtHZ; - struct blasfeo_dvec *xy; - struct blasfeo_dvec *Yxy; - struct blasfeo_dvec *xz; - struct blasfeo_dvec *tmp_nv; - struct blasfeo_dvec *tmp_2ns; - struct blasfeo_dvec *tmp_nv2ns; - struct blasfeo_dmat *A_li; // A of linearly independent equality constraints - struct blasfeo_dvec *b_li; // b of linearly independent equality constraints - struct blasfeo_dmat *A_bkp; // pointer to backup A - struct blasfeo_dvec *b_bkp; // pointer to backup b - struct blasfeo_dmat *Ab_LU; - double *stat; // convergence statistics - int *ipiv_v; - int *ipiv_e; - int *ipiv_e1; - void *lq_work0; - void *lq_work1; - void *lq_work_null; - void *orglq_work_null; - int iter; // iteration number - int stat_max; // iterations saved in stat - int stat_m; // numer of recorded stat per ipm iter - int scale; - int use_hess_fact; - int use_A_fact; - int status; - int lq_fact; // cache from arg - int mask_constr; // use constr mask - int ne_li; // number of linearly independent equality constraints - int ne_bkp; // ne backup - hpipm_size_t memsize; // memory size (in bytes) of workspace - }; - - - -// -hpipm_size_t d_dense_qp_ipm_arg_memsize(struct d_dense_qp_dim *dim); -// -void d_dense_qp_ipm_arg_create(struct d_dense_qp_dim *dim, struct d_dense_qp_ipm_arg *arg, void *mem); -// -void d_dense_qp_ipm_arg_set_default(enum hpipm_mode mode, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set(char *field, void *value, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_iter_max(int *iter_max, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_alpha_min(double *alpha_min, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_mu0(double *mu0, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_tol_stat(double *tol_stat, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_tol_eq(double *tol_eq, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_tol_ineq(double *tol_ineq, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_tol_comp(double *tol_comp, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_reg_prim(double *reg, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_reg_dual(double *reg, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_warm_start(int *warm_start, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_pred_corr(int *pred_corr, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_cond_pred_corr(int *cond_pred_corr, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_comp_res_pred(int *comp_res_pred, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_comp_res_exit(int *comp_res_exit, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_lam_min(double *value, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_t_min(double *value, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_tau_min(double *value, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_kkt_fact_alg(int *value, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_remove_lin_dep_eq(int *value, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_compute_obj(int *value, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_t_lam_min(int *value, struct d_dense_qp_ipm_arg *arg); - -// -void d_dense_qp_ipm_arg_set_split_step(int *value, struct d_dense_qp_ipm_arg *arg); - -// -hpipm_size_t d_dense_qp_ipm_ws_memsize(struct d_dense_qp_dim *qp_dim, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_ws_create(struct d_dense_qp_dim *qp_dim, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws, void *mem); -// -void d_dense_qp_ipm_get(char *field, struct d_dense_qp_ipm_ws *ws, void *value); -// -void d_dense_qp_ipm_get_status(struct d_dense_qp_ipm_ws *ws, int *status); -// -void d_dense_qp_ipm_get_iter(struct d_dense_qp_ipm_ws *ws, int *iter); -// -void d_dense_qp_ipm_get_max_res_stat(struct d_dense_qp_ipm_ws *ws, double *res_stat); -// -void d_dense_qp_ipm_get_max_res_eq(struct d_dense_qp_ipm_ws *ws, double *res_eq); -// -void d_dense_qp_ipm_get_max_res_ineq(struct d_dense_qp_ipm_ws *ws, double *res_ineq); -// -void d_dense_qp_ipm_get_max_res_comp(struct d_dense_qp_ipm_ws *ws, double *res_comp); -// -void d_dense_qp_ipm_get_stat(struct d_dense_qp_ipm_ws *ws, double **stat); -// -void d_dense_qp_ipm_get_stat_m(struct d_dense_qp_ipm_ws *ws, int *stat_m); -// -void d_dense_qp_init_var(struct d_dense_qp *qp, struct d_dense_qp_sol *qp_sol, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws); -// -void d_dense_qp_ipm_abs_step(int kk, struct d_dense_qp *qp, struct d_dense_qp_sol *qp_sol, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws); -// -void d_dense_qp_ipm_delta_step(int kk, struct d_dense_qp *qp, struct d_dense_qp_sol *qp_sol, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws); -// -void d_dense_qp_ipm_solve(struct d_dense_qp *qp, struct d_dense_qp_sol *qp_sol, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws); -// -void d_dense_qp_ipm_predict(struct d_dense_qp *qp, struct d_dense_qp_sol *qp_sol, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws); -// -void d_dense_qp_ipm_sens(struct d_dense_qp *qp, struct d_dense_qp_sol *qp_sol, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws); -// -void d_dense_qp_compute_step_length(struct d_dense_qp *qp, struct d_dense_qp_sol *qp_sol, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_DENSE_QP_IPM_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_kkt.h b/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_kkt.h deleted file mode 100644 index 6d05779f4b..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_kkt.h +++ /dev/null @@ -1,72 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_D_DENSE_QP_KKT_H_ -#define HPIPM_D_DENSE_QP_KKT_H_ - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void d_fact_solve_kkt_unconstr_dense_qp(struct d_dense_qp *qp, struct d_dense_qp_sol *qp_sol, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws); -// -void d_fact_solve_kkt_step_dense_qp(struct d_dense_qp *qp, struct d_dense_qp_sol *qp_sol, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws); -// -void d_fact_lq_solve_kkt_step_dense_qp(struct d_dense_qp *qp, struct d_dense_qp_sol *qp_sol, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws); -// -void d_solve_kkt_step_dense_qp(struct d_dense_qp *qp, struct d_dense_qp_sol *qp_sol, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws); -// -void d_dense_qp_remove_lin_dep_eq(struct d_dense_qp *qp, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws); -// -void d_dense_qp_restore_lin_dep_eq(struct d_dense_qp *qp, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws); -// -void d_dense_qp_compute_obj(struct d_dense_qp *qp, struct d_dense_qp_sol *qp_sol, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_DENSE_QP_KKT_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_res.h b/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_res.h deleted file mode 100644 index 7c2023257a..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_res.h +++ /dev/null @@ -1,105 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_DENSE_QP_RES_H_ -#define HPIPM_D_DENSE_QP_RES_H_ - - - -#include -#include - -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_dense_qp_res - { - struct d_dense_qp_dim *dim; - struct blasfeo_dvec *res_g; // q-residuals - struct blasfeo_dvec *res_b; // b-residuals - struct blasfeo_dvec *res_d; // d-residuals - struct blasfeo_dvec *res_m; // m-residuals - double res_max[4]; // max of residuals - double res_mu; // mu-residual - hpipm_size_t memsize; - }; - - - -struct d_dense_qp_res_ws - { - struct blasfeo_dvec *tmp_nbg; // work space of size nbM+ngM - struct blasfeo_dvec *tmp_ns; // work space of size nsM - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_dense_qp_res_memsize(struct d_dense_qp_dim *dim); -// -void d_dense_qp_res_create(struct d_dense_qp_dim *dim, struct d_dense_qp_res *res, void *mem); -// -hpipm_size_t d_dense_qp_res_ws_memsize(struct d_dense_qp_dim *dim); -// -void d_dense_qp_res_ws_create(struct d_dense_qp_dim *dim, struct d_dense_qp_res_ws *workspace, void *mem); -// -void d_dense_qp_res_compute(struct d_dense_qp *qp, struct d_dense_qp_sol *qp_sol, struct d_dense_qp_res *res, struct d_dense_qp_res_ws *ws); -// -void d_dense_qp_res_compute_lin(struct d_dense_qp *qp, struct d_dense_qp_sol *qp_sol, struct d_dense_qp_sol *qp_step, struct d_dense_qp_res *res, struct d_dense_qp_res_ws *ws); -// -void d_dense_qp_res_compute_inf_norm(struct d_dense_qp_res *res); -// -void d_dense_qp_res_get_all(struct d_dense_qp_res *res, double *res_g, double *res_ls, double *res_us, double *res_b, double *res_d_lb, double *res_d_ub, double *res_d_lg, double *res_d_ug, double *res_d_ls, double *res_d_us, double *res_m_lb, double *res_m_ub, double *res_m_lg, double *res_m_ug, double *res_m_ls, double *res_m_us); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_D_DENSE_QP_RES_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_sol.h b/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_sol.h deleted file mode 100644 index aaa3fdb0e4..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_sol.h +++ /dev/null @@ -1,94 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_D_DENSE_QP_SOL_H_ -#define HPIPM_D_DENSE_QP_SOL_H_ - - - -#include -#include - -#include "hpipm_d_dense_qp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_dense_qp_sol - { - struct d_dense_qp_dim *dim; - struct blasfeo_dvec *v; - struct blasfeo_dvec *pi; - struct blasfeo_dvec *lam; - struct blasfeo_dvec *t; - void *misc; - double obj; - int valid_obj; - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_dense_qp_sol_memsize(struct d_dense_qp_dim *dim); -// -void d_dense_qp_sol_create(struct d_dense_qp_dim *dim, struct d_dense_qp_sol *qp_sol, void *memory); -// -void d_dense_qp_sol_get_all(struct d_dense_qp_sol *qp_sol, double *v, double *ls, double *us, double *pi, double *lam_lb, double *lam_ub, double *lam_lg, double *lam_ug, double *lam_ls, double *lam_us); -// -void d_dense_qp_sol_get(char *field, struct d_dense_qp_sol *sol, void *value); -// -void d_dense_qp_sol_get_v(struct d_dense_qp_sol *sol, double *v); -// -void d_dense_qp_sol_get_valid_obj(struct d_dense_qp_sol *sol, int *valid_obj); -// -void d_dense_qp_sol_get_obj(struct d_dense_qp_sol *sol, double *obj); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_DENSE_QP_SOL_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_utils.h b/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_utils.h deleted file mode 100644 index ccb77aaca3..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_utils.h +++ /dev/null @@ -1,83 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_DENSE_QP_UTILS_H_ -#define HPIPM_D_DENSE_QP_UTILS_H_ - - - -#include -#include - -#include "hpipm_d_dense_qp_dim.h" -#include "hpipm_d_dense_qp.h" -#include "hpipm_d_dense_qp_sol.h" -#include "hpipm_d_dense_qp_ipm.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void d_dense_qp_dim_print(struct d_dense_qp_dim *qp_dim); -// -//void d_dense_qp_dim_codegen(char *file_name, char *mode, struct d_dense_qp_dim *qp_dim); -// -void d_dense_qp_print(struct d_dense_qp_dim *qp_dim, struct d_dense_qp *qp); -// -//void d_dense_qp_codegen(char *file_name, char *mode, struct d_dense_qp_dim *qp_dim, struct d_dense_qp *qp); -// -void d_dense_qp_sol_print(struct d_dense_qp_dim *qp_dim, struct d_dense_qp_sol *dense_qp_sol); -// -//void d_dense_qp_ipm_arg_codegen(char *file_name, char *mode, struct d_dense_qp_dim *qp_dim, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_res_print(struct d_dense_qp_dim *qp_dim, struct d_dense_qp_res *dense_qp_res); -// -void d_dense_qp_arg_print(struct d_dense_qp_dim *qp_dim, struct d_dense_qp_ipm_arg *qp_ipm_arg); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_DENSE_QP_UTILS_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp.h b/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp.h deleted file mode 100644 index 240c9b04be..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp.h +++ /dev/null @@ -1,303 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_OCP_QCQP_H_ -#define HPIPM_D_OCP_QCQP_H_ - - - -#include -#include - -#include "hpipm_d_ocp_qcqp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_ocp_qcqp - { - struct d_ocp_qcqp_dim *dim; - struct blasfeo_dmat *BAbt; // dynamics matrix & vector work space - struct blasfeo_dmat *RSQrq; // hessian of cost & vector work space - struct blasfeo_dmat *DCt; // inequality constraints matrix - struct blasfeo_dmat **Hq; // hessians of quadratic constraints - struct blasfeo_dvec *b; // dynamics vector - struct blasfeo_dvec *rqz; // gradient of cost & gradient of slacks - struct blasfeo_dvec *d; // inequality constraints vector - struct blasfeo_dvec *d_mask; // inequality constraints mask vector - struct blasfeo_dvec *m; // rhs of complementarity condition - struct blasfeo_dvec *Z; // (diagonal) hessian of slacks - int **idxb; // indices of box constrained variables within [u; x] - int **idxs_rev; // index of soft constraints (reverse storage) - int **Hq_nzero; // for each int, the last 3 bits ...abc, {a,b,c}=0 => {R,S,Q}=0 - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t d_ocp_qcqp_strsize(); -// -hpipm_size_t d_ocp_qcqp_memsize(struct d_ocp_qcqp_dim *dim); -// -void d_ocp_qcqp_create(struct d_ocp_qcqp_dim *dim, struct d_ocp_qcqp *qp, void *memory); -// -void d_ocp_qcqp_copy_all(struct d_ocp_qcqp *qp_orig, struct d_ocp_qcqp *qp_dest); - -// setters -// -void d_ocp_qcqp_set_all_zero(struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_rhs_zero(struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set(char *field_name, int stage, void *value, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_el(char *field_name, int stage, int index, void *value, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_A(int stage, double *mat, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_B(int stage, double *mat, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_b(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_Q(int stage, double *mat, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_S(int stage, double *mat, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_R(int stage, double *mat, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_q(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_r(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_lb(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_lb_mask(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_ub(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_ub_mask(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_lbx(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_lbx_mask(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_el_lbx(int stage, int index, double *elem, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_ubx(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_ubx_mask(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_el_ubx(int stage, int index, double *elem, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_lbu(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_lbu_mask(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_ubu(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_ubu_mask(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_idxb(int stage, int *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_idxbx(int stage, int *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_Jbx(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_idxbu(int stage, int *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_Jbu(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_C(int stage, double *mat, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_D(int stage, double *mat, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_lg(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_lg_mask(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_ug(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_ug_mask(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_Qq(int stage, double *mat, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_Sq(int stage, double *mat, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_Rq(int stage, double *mat, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_qq(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_rq(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_uq(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_uq_mask(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_Zl(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_Zu(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_zl(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_zu(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_lls(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_lls_mask(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_lus(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_lus_mask(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_idxs(int stage, int *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_idxs_rev(int stage, int *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_Jsbu(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_Jsbx(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_Jsg(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_Jsq(int stage, double *vec, struct d_ocp_qcqp *qp); - -// getters -// -void d_ocp_qcqp_get(char *field, int stage, struct d_ocp_qcqp *qp, void *value); -// -void d_ocp_qcqp_get_A(int stage, struct d_ocp_qcqp *qp, double *mat); -// -void d_ocp_qcqp_get_B(int stage, struct d_ocp_qcqp *qp, double *mat); -// -void d_ocp_qcqp_get_b(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_Q(int stage, struct d_ocp_qcqp *qp, double *mat); -// -void d_ocp_qcqp_get_S(int stage, struct d_ocp_qcqp *qp, double *mat); -// -void d_ocp_qcqp_get_R(int stage, struct d_ocp_qcqp *qp, double *mat); -// -void d_ocp_qcqp_get_q(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_r(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_ub(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_ub_mask(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_lb(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_lb_mask(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_lbx(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_lbx_mask(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_ubx(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_ubx_mask(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_lbu(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_lbu_mask(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_ubu(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_ubu_mask(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_idxb(int stage, struct d_ocp_qcqp *qp, int *vec); -// -//void d_ocp_qcqp_get_idxbx(int stage, struct d_ocp_qcqp *qp, int *vec); -// -//void d_ocp_qcqp_get_Jbx(int stage, struct d_ocp_qcqp *qp, double *vec); -// -//void d_ocp_qcqp_get_idxbu(int stage, struct d_ocp_qcqp *qp, int *vec); -// -//void d_ocp_qcqp_get_Jbu(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_C(int stage, struct d_ocp_qcqp *qp, double *mat); -// -void d_ocp_qcqp_get_D(int stage, struct d_ocp_qcqp *qp, double *mat); -// -void d_ocp_qcqp_get_lg(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_lg_mask(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_ug(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_ug_mask(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_Zl(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_Zu(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_zl(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_zu(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_lls(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_lls_mask(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_lus(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_lus_mask(int stage, struct d_ocp_qcqp *qp, double *vec); -// XXX only valid if there is one slack per softed constraint !!! -void d_ocp_qcqp_get_idxs(int stage, struct d_ocp_qcqp *qp, int *vec); -// -void d_ocp_qcqp_get_idxs_rev(int stage, struct d_ocp_qcqp *qp, int *vec); -// -//void d_ocp_qcqp_get_Jsbu(int stage, struct d_ocp_qcqp *qp, float *vec); -// -//void d_ocp_qcqp_get_Jsbx(int stage, struct d_ocp_qcqp *qp, float *vec); -// -//void d_ocp_qcqp_get_Jsg(int stage, struct d_ocp_qcqp *qp, float *vec); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_OCP_QCQP_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_dim.h b/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_dim.h deleted file mode 100644 index 268628a2b2..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_dim.h +++ /dev/null @@ -1,118 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_OCP_QCQP_DIM_H_ -#define HPIPM_D_OCP_QCQP_DIM_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_ocp_qcqp_dim - { - struct d_ocp_qp_dim *qp_dim; // dim of qp approximation - int *nx; // number of states - int *nu; // number of inputs - int *nb; // number of box constraints - int *nbx; // number of (two-sided) state box constraints - int *nbu; // number of (two-sided) input box constraints - int *ng; // number of (two-sided) general constraints - int *nq; // number of (upper) quadratic constraints - int *ns; // number of soft constraints - int *nsbx; // number of (two-sided) soft state box constraints - int *nsbu; // number of (two-sided) soft input box constraints - int *nsg; // number of (two-sided) soft general constraints - int *nsq; // number of (upper) soft quadratic constraints - int N; // horizon length - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_ocp_qcqp_dim_strsize(); -// -hpipm_size_t d_ocp_qcqp_dim_memsize(int N); -// -void d_ocp_qcqp_dim_create(int N, struct d_ocp_qcqp_dim *qp_dim, void *memory); -// -void d_ocp_qcqp_dim_copy_all(struct d_ocp_qcqp_dim *dim_orig, struct d_ocp_qcqp_dim *dim_dest); -// -void d_ocp_qcqp_dim_set(char *field, int stage, int value, struct d_ocp_qcqp_dim *dim); -// -void d_ocp_qcqp_dim_set_nx(int stage, int value, struct d_ocp_qcqp_dim *dim); -// -void d_ocp_qcqp_dim_set_nu(int stage, int value, struct d_ocp_qcqp_dim *dim); -// -void d_ocp_qcqp_dim_set_nbx(int stage, int value, struct d_ocp_qcqp_dim *dim); -// -void d_ocp_qcqp_dim_set_nbu(int stage, int value, struct d_ocp_qcqp_dim *dim); -// -void d_ocp_qcqp_dim_set_ng(int stage, int value, struct d_ocp_qcqp_dim *dim); -// -void d_ocp_qcqp_dim_set_nq(int stage, int value, struct d_ocp_qcqp_dim *dim); -// -void d_ocp_qcqp_dim_set_ns(int stage, int value, struct d_ocp_qcqp_dim *dim); -// -void d_ocp_qcqp_dim_set_nsbx(int stage, int value, struct d_ocp_qcqp_dim *dim); -// -void d_ocp_qcqp_dim_set_nsbu(int stage, int value, struct d_ocp_qcqp_dim *dim); -// -void d_ocp_qcqp_dim_set_nsg(int stage, int value, struct d_ocp_qcqp_dim *dim); -// -void d_ocp_qcqp_dim_set_nsq(int stage, int value, struct d_ocp_qcqp_dim *dim); -// -void d_ocp_qcqp_dim_get(struct d_ocp_qcqp_dim *dim, char *field, int stage, int *value); -// -void d_ocp_qcqp_dim_get_N(struct d_ocp_qcqp_dim *dim, int *value); -// -void d_ocp_qcqp_dim_get_nx(struct d_ocp_qcqp_dim *dim, int stage, int *value); -// -void d_ocp_qcqp_dim_get_nu(struct d_ocp_qcqp_dim *dim, int stage, int *value); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_OCP_QCQP_DIM_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_ipm.h b/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_ipm.h deleted file mode 100644 index 99f2329dcc..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_ipm.h +++ /dev/null @@ -1,190 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_OCP_QCQP_IPM_H_ -#define HPIPM_D_OCP_QCQP_IPM_H_ - - - -#include -#include - -#include -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_ocp_qcqp_ipm_arg - { - struct d_ocp_qp_ipm_arg *qp_arg; - double mu0; // initial value for complementarity slackness - double alpha_min; // exit cond on step length - double res_g_max; // exit cond on inf norm of residuals - double res_b_max; // exit cond on inf norm of residuals - double res_d_max; // exit cond on inf norm of residuals - double res_m_max; // exit cond on inf norm of residuals - double reg_prim; // reg of primal hessian - double lam_min; // min value in lam vector - double t_min; // min value in t vector - int iter_max; // exit cond in iter number - int stat_max; // iterations saved in stat - int pred_corr; // use Mehrotra's predictor-corrector IPM algirthm - int cond_pred_corr; // conditional Mehrotra's predictor-corrector - int itref_pred_max; // max number of iterative refinement steps for predictor step - int itref_corr_max; // max number of iterative refinement steps for corrector step - int warm_start; // 0 no warm start, 1 warm start primal sol, 2 warm start primal and dual sol - int square_root_alg; // 0 classical Riccati, 1 square-root Riccati - int lq_fact; // 0 syrk+potrf, 1 mix, 2 lq (for square_root_alg==1) - int abs_form; // absolute IPM formulation - int comp_dual_sol_eq; // dual solution of equality constrains (only for abs_form==1) - int comp_res_exit; // compute residuals on exit (only for abs_form==1 and comp_dual_sol_eq==1) - int comp_res_pred; // compute residuals of prediction - int split_step; // use different step for primal and dual variables - int t_lam_min; // clip t and lam: 0 no, 1 in Gamma computation, 2 in solution - int mode; - hpipm_size_t memsize; - }; - - - -struct d_ocp_qcqp_ipm_ws - { - struct d_ocp_qp_ipm_ws *qp_ws; - struct d_ocp_qp *qp; - struct d_ocp_qp_sol *qp_sol; - struct d_ocp_qcqp_res_ws *qcqp_res_ws; - struct d_ocp_qcqp_res *qcqp_res; - struct blasfeo_dvec *tmp_nuxM; - int iter; // iteration number - int status; - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_ocp_qcqp_ipm_arg_strsize(); -// -hpipm_size_t d_ocp_qcqp_ipm_arg_memsize(struct d_ocp_qcqp_dim *ocp_dim); -// -void d_ocp_qcqp_ipm_arg_create(struct d_ocp_qcqp_dim *ocp_dim, struct d_ocp_qcqp_ipm_arg *arg, void *mem); -// -void d_ocp_qcqp_ipm_arg_set_default(enum hpipm_mode mode, struct d_ocp_qcqp_ipm_arg *arg); -// -void d_ocp_qcqp_ipm_arg_set(char *field, void *value, struct d_ocp_qcqp_ipm_arg *arg); -// set maximum number of iterations -void d_ocp_qcqp_ipm_arg_set_iter_max(int *value, struct d_ocp_qcqp_ipm_arg *arg); -// set minimum step lenght -void d_ocp_qcqp_ipm_arg_set_alpha_min(double *value, struct d_ocp_qcqp_ipm_arg *arg); -// set initial value of barrier parameter -void d_ocp_qcqp_ipm_arg_set_mu0(double *value, struct d_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on stationarity condition -void d_ocp_qcqp_ipm_arg_set_tol_stat(double *value, struct d_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on equality constr -void d_ocp_qcqp_ipm_arg_set_tol_eq(double *value, struct d_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on inequality constr -void d_ocp_qcqp_ipm_arg_set_tol_ineq(double *value, struct d_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on complementarity condition -void d_ocp_qcqp_ipm_arg_set_tol_comp(double *value, struct d_ocp_qcqp_ipm_arg *arg); -// set regularization of primal variables -void d_ocp_qcqp_ipm_arg_set_reg_prim(double *value, struct d_ocp_qcqp_ipm_arg *arg); -// set warm start: 0 no warm start, 1 primal var -void d_ocp_qcqp_ipm_arg_set_warm_start(int *value, struct d_ocp_qcqp_ipm_arg *arg); -// Mehrotra's predictor-corrector IPM algorithm: 0 no predictor-corrector, 1 use predictor-corrector -void d_ocp_qcqp_ipm_arg_set_pred_corr(int *value, struct d_ocp_qcqp_ipm_arg *arg); -// conditional predictor-corrector: 0 no conditinal predictor-corrector, 1 conditional predictor-corrector -void d_ocp_qcqp_ipm_arg_set_cond_pred_corr(int *value, struct d_ocp_qcqp_ipm_arg *arg); -// set riccati algorithm: 0 classic, 1 square-root -void d_ocp_qcqp_ipm_arg_set_ric_alg(int *value, struct d_ocp_qcqp_ipm_arg *arg); -// compute residuals after solution -void d_ocp_qcqp_ipm_arg_set_comp_res_exit(int *value, struct d_ocp_qcqp_ipm_arg *arg); -// compute residuals of prediction -void d_ocp_qcqp_ipm_arg_set_comp_res_pred(int *value, struct d_ocp_qcqp_ipm_arg *arg); -// min value of lam in the solution -void d_ocp_qcqp_ipm_arg_set_lam_min(double *value, struct d_ocp_qcqp_ipm_arg *arg); -// min value of t in the solution -void d_ocp_qcqp_ipm_arg_set_t_min(double *value, struct d_ocp_qcqp_ipm_arg *arg); -// use different step for primal and dual variables -void d_ocp_qcqp_ipm_arg_set_split_step(int *value, struct d_ocp_qcqp_ipm_arg *arg); -// clip t and lam: 0 no, 1 in Gamma computation, 2 in solution -void d_ocp_qcqp_ipm_arg_set_t_lam_min(int *value, struct d_ocp_qcqp_ipm_arg *arg); - -// -hpipm_size_t d_ocp_qcqp_ipm_ws_strsize(); -// -hpipm_size_t d_ocp_qcqp_ipm_ws_memsize(struct d_ocp_qcqp_dim *ocp_dim, struct d_ocp_qcqp_ipm_arg *arg); -// -void d_ocp_qcqp_ipm_ws_create(struct d_ocp_qcqp_dim *ocp_dim, struct d_ocp_qcqp_ipm_arg *arg, struct d_ocp_qcqp_ipm_ws *ws, void *mem); -// -void d_ocp_qcqp_ipm_get(char *field, struct d_ocp_qcqp_ipm_ws *ws, void *value); -// -void d_ocp_qcqp_ipm_get_status(struct d_ocp_qcqp_ipm_ws *ws, int *status); -// -void d_ocp_qcqp_ipm_get_iter(struct d_ocp_qcqp_ipm_ws *ws, int *iter); -// -void d_ocp_qcqp_ipm_get_max_res_stat(struct d_ocp_qcqp_ipm_ws *ws, double *res_stat); -// -void d_ocp_qcqp_ipm_get_max_res_eq(struct d_ocp_qcqp_ipm_ws *ws, double *res_eq); -// -void d_ocp_qcqp_ipm_get_max_res_ineq(struct d_ocp_qcqp_ipm_ws *ws, double *res_ineq); -// -void d_ocp_qcqp_ipm_get_max_res_comp(struct d_ocp_qcqp_ipm_ws *ws, double *res_comp); -// -void d_ocp_qcqp_ipm_get_stat(struct d_ocp_qcqp_ipm_ws *ws, double **stat); -// -void d_ocp_qcqp_ipm_get_stat_m(struct d_ocp_qcqp_ipm_ws *ws, int *stat_m); -// -void d_ocp_qcqp_init_var(struct d_ocp_qcqp *qp, struct d_ocp_qcqp_sol *qp_sol, struct d_ocp_qcqp_ipm_arg *arg, struct d_ocp_qcqp_ipm_ws *ws); -// -void d_ocp_qcqp_ipm_solve(struct d_ocp_qcqp *qp, struct d_ocp_qcqp_sol *qp_sol, struct d_ocp_qcqp_ipm_arg *arg, struct d_ocp_qcqp_ipm_ws *ws); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_D_OCP_QCQP_IPM_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_res.h b/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_res.h deleted file mode 100644 index 077f134677..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_res.h +++ /dev/null @@ -1,114 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_OCP_QCQP_RES_H_ -#define HPIPM_D_OCP_QCQP_RES_H_ - - - -#include -#include - -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_ocp_qcqp_res - { - struct d_ocp_qcqp_dim *dim; - struct blasfeo_dvec *res_g; // q-residuals - struct blasfeo_dvec *res_b; // b-residuals - struct blasfeo_dvec *res_d; // d-residuals - struct blasfeo_dvec *res_m; // m-residuals - double res_max[4]; // max of residuals - double res_mu; // mu-residual - hpipm_size_t memsize; - }; - - - -struct d_ocp_qcqp_res_ws - { - struct blasfeo_dvec *tmp_nuxM; // work space of size nuM+nxM - struct blasfeo_dvec *tmp_nbgqM; // work space of size nbM+ngM+nqM - struct blasfeo_dvec *tmp_nsM; // work space of size nsM - struct blasfeo_dvec *q_fun; // value for evaluation of quadr constr - struct blasfeo_dvec *q_adj; // value for adjoint of quadr constr - int use_q_fun; // reuse cached value for evaluation of quadr constr - int use_q_adj; // reuse cached value for adjoint of quadr constr - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_ocp_qcqp_res_memsize(struct d_ocp_qcqp_dim *ocp_dim); -// -void d_ocp_qcqp_res_create(struct d_ocp_qcqp_dim *ocp_dim, struct d_ocp_qcqp_res *res, void *mem); -// -hpipm_size_t d_ocp_qcqp_res_ws_memsize(struct d_ocp_qcqp_dim *ocp_dim); -// -void d_ocp_qcqp_res_ws_create(struct d_ocp_qcqp_dim *ocp_dim, struct d_ocp_qcqp_res_ws *workspace, void *mem); -// -void d_ocp_qcqp_res_compute(struct d_ocp_qcqp *qp, struct d_ocp_qcqp_sol *qp_sol, struct d_ocp_qcqp_res *res, struct d_ocp_qcqp_res_ws *ws); -// -void d_ocp_qcqp_res_compute_inf_norm(struct d_ocp_qcqp_res *res); -// -void d_ocp_qcqp_res_get_max_res_stat(struct d_ocp_qcqp_res *res, double *value); -// -void d_ocp_qcqp_res_get_max_res_eq(struct d_ocp_qcqp_res *res, double *value); -// -void d_ocp_qcqp_res_get_max_res_ineq(struct d_ocp_qcqp_res *res, double *value); -// -void d_ocp_qcqp_res_get_max_res_comp(struct d_ocp_qcqp_res *res, double *value); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_D_OCP_QCQP_RES_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_sol.h b/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_sol.h deleted file mode 100644 index 68adbfce2d..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_sol.h +++ /dev/null @@ -1,114 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_OCP_QCQP_SOL_H_ -#define HPIPM_D_OCP_QCQP_SOL_H_ - - - -#include -#include - -#include "hpipm_d_ocp_qcqp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_ocp_qcqp_sol - { - struct d_ocp_qcqp_dim *dim; - struct blasfeo_dvec *ux; - struct blasfeo_dvec *pi; - struct blasfeo_dvec *lam; - struct blasfeo_dvec *t; - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t d_ocp_qcqp_sol_strsize(); -// -hpipm_size_t d_ocp_qcqp_sol_memsize(struct d_ocp_qcqp_dim *dim); -// -void d_ocp_qcqp_sol_create(struct d_ocp_qcqp_dim *dim, struct d_ocp_qcqp_sol *qp_sol, void *memory); -// -void d_ocp_qcqp_sol_copy_all(struct d_ocp_qcqp_sol *qp_sol_orig, struct d_ocp_qcqp_sol *qp_sol_dest); -// -void d_ocp_qcqp_sol_get(char *field, int stage, struct d_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_ocp_qcqp_sol_get_u(int stage, struct d_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_ocp_qcqp_sol_get_x(int stage, struct d_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_ocp_qcqp_sol_get_sl(int stage, struct d_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_ocp_qcqp_sol_get_su(int stage, struct d_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_ocp_qcqp_sol_get_pi(int stage, struct d_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_ocp_qcqp_sol_get_lam_lb(int stage, struct d_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_ocp_qcqp_sol_get_lam_ub(int stage, struct d_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_ocp_qcqp_sol_get_lam_lg(int stage, struct d_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_ocp_qcqp_sol_get_lam_ug(int stage, struct d_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_ocp_qcqp_sol_set(char *field, int stage, double *vec, struct d_ocp_qcqp_sol *qp_sol); -// -void d_ocp_qcqp_sol_set_u(int stage, double *vec, struct d_ocp_qcqp_sol *qp_sol); -// -void d_ocp_qcqp_sol_set_x(int stage, double *vec, struct d_ocp_qcqp_sol *qp_sol); -// -void d_ocp_qcqp_sol_set_sl(int stage, double *vec, struct d_ocp_qcqp_sol *qp_sol); -// -void d_ocp_qcqp_sol_set_su(int stage, double *vec, struct d_ocp_qcqp_sol *qp_sol); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_OCP_QCQP_SOL_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_utils.h b/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_utils.h deleted file mode 100644 index 00248f1dbe..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_utils.h +++ /dev/null @@ -1,81 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_OCP_QCQP_UTILS_H_ -#define HPIPM_D_OCP_QCQP_UTILS_H_ - - - -#include -#include - -#include "hpipm_d_ocp_qcqp_dim.h" -#include "hpipm_d_ocp_qp.h" -#include "hpipm_d_ocp_qcqp_sol.h" -#include "hpipm_d_ocp_qcqp_ipm.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void d_ocp_qcqp_dim_print(struct d_ocp_qcqp_dim *qcqp_dim); -// -void d_ocp_qcqp_dim_codegen(char *file_name, char *mode, struct d_ocp_qcqp_dim *qcqp_dim); -// -void d_ocp_qcqp_print(struct d_ocp_qcqp_dim *qcqp_dim, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_codegen(char *file_name, char *mode, struct d_ocp_qcqp_dim *qcqp_dim, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_sol_print(struct d_ocp_qcqp_dim *qcqp_dim, struct d_ocp_qcqp_sol *ocp_qcqp_sol); -// -void d_ocp_qcqp_ipm_arg_codegen(char *file_name, char *mode, struct d_ocp_qcqp_dim *qcqp_dim, struct d_ocp_qcqp_ipm_arg *arg); -// -void d_ocp_qcqp_res_print(struct d_ocp_qcqp_dim *qcqp_dim, struct d_ocp_qcqp_res *ocp_qcqp_res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_OCP_QCQP_UTILS_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp.h b/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp.h deleted file mode 100644 index ca26cdba34..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp.h +++ /dev/null @@ -1,306 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_OCP_QP_H_ -#define HPIPM_D_OCP_QP_H_ - - - -#include -#include - -#include "hpipm_d_ocp_qp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_ocp_qp - { - struct d_ocp_qp_dim *dim; - struct blasfeo_dmat *BAbt; // dynamics matrix & vector work space - struct blasfeo_dmat *RSQrq; // hessian of cost & vector work space - struct blasfeo_dmat *DCt; // inequality constraints matrix - struct blasfeo_dvec *b; // dynamics vector - struct blasfeo_dvec *rqz; // gradient of cost & gradient of slacks - struct blasfeo_dvec *d; // inequality constraints vector - struct blasfeo_dvec *d_mask; // inequality constraints mask vector - struct blasfeo_dvec *m; // rhs of complementarity condition - struct blasfeo_dvec *Z; // (diagonal) hessian of slacks - int **idxb; // indices of box constrained variables within [u; x] - int **idxs_rev; // index of soft constraints (reverse storage) - int **idxe; // indices of constraints within [bu, bx, g] that are equalities, subset of [0, ..., nbu+nbx+ng-1] - int *diag_H_flag; // flag the fact that Hessian is diagonal - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t d_ocp_qp_strsize(); -// -hpipm_size_t d_ocp_qp_memsize(struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_create(struct d_ocp_qp_dim *dim, struct d_ocp_qp *qp, void *memory); -// -void d_ocp_qp_copy_all(struct d_ocp_qp *qp_orig, struct d_ocp_qp *qp_dest); - -// setters -// -void d_ocp_qp_set_all_zero(struct d_ocp_qp *qp); -// -void d_ocp_qp_set_rhs_zero(struct d_ocp_qp *qp); -// -void d_ocp_qp_set_all(double **A, double **B, double **b, double **Q, double **S, double **R, double **q, double **r, int **idxbx, double **lbx, double **ubx, int **idxbu, double **lbu, double **ubu, double **C, double **D, double **lg, double **ug, double **Zl, double **Zu, double **zl, double **zu, int **idxs, double **ls, double **us, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_all_rowmaj(double **A, double **B, double **b, double **Q, double **S, double **R, double **q, double **r, int **idxbx, double **lbx, double **ubx, int **idxbu, double **lbu, double **ubu, double **C, double **D, double **lg, double **ug, double **Zl, double **Zu, double **zl, double **zu, int **idxs, double **ls, double **us, struct d_ocp_qp *qp); -// -void d_ocp_qp_set(char *field_name, int stage, void *value, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_el(char *field_name, int stage, int index, void *value, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_A(int stage, double *mat, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_B(int stage, double *mat, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_b(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_Q(int stage, double *mat, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_S(int stage, double *mat, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_R(int stage, double *mat, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_q(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_r(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_lb(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_lb_mask(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_ub(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_ub_mask(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_lbx(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_lbx_mask(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_el_lbx(int stage, int index, double *elem, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_ubx(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_ubx_mask(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_el_ubx(int stage, int index, double *elem, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_lbu(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_lbu_mask(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_ubu(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_ubu_mask(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_idxb(int stage, int *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_idxbx(int stage, int *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_Jbx(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_idxbu(int stage, int *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_Jbu(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_C(int stage, double *mat, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_D(int stage, double *mat, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_lg(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_lg_mask(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_ug(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_ug_mask(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_Zl(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_Zu(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_zl(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_zu(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_lls(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_lls_mask(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_lus(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_lus_mask(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_idxs(int stage, int *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_idxs_rev(int stage, int *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_Jsbu(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_Jsbx(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_Jsg(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_idxe(int stage, int *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_idxbxe(int stage, int *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_idxbue(int stage, int *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_idxge(int stage, int *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_Jbxe(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_Jbue(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_Jge(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_diag_H_flag(int stage, int *value, struct d_ocp_qp *qp); - -// getters -// -void d_ocp_qp_get(char *field, int stage, struct d_ocp_qp *qp, void *value); -// -void d_ocp_qp_get_A(int stage, struct d_ocp_qp *qp, double *mat); -// -void d_ocp_qp_get_B(int stage, struct d_ocp_qp *qp, double *mat); -// -void d_ocp_qp_get_b(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_Q(int stage, struct d_ocp_qp *qp, double *mat); -// -void d_ocp_qp_get_S(int stage, struct d_ocp_qp *qp, double *mat); -// -void d_ocp_qp_get_R(int stage, struct d_ocp_qp *qp, double *mat); -// -void d_ocp_qp_get_q(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_r(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_ub(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_ub_mask(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_lb(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_lb_mask(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_lbx(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_lbx_mask(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_ubx(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_ubx_mask(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_lbu(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_lbu_mask(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_ubu(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_ubu_mask(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_idxb(int stage, struct d_ocp_qp *qp, int *vec); -// -//void d_ocp_qp_get_idxbx(int stage, struct d_ocp_qp *qp, int *vec); -// -//void d_ocp_qp_get_Jbx(int stage, struct d_ocp_qp *qp, double *vec); -// -//void d_ocp_qp_get_idxbu(int stage, struct d_ocp_qp *qp, int *vec); -// -//void d_ocp_qp_get_Jbu(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_C(int stage, struct d_ocp_qp *qp, double *mat); -// -void d_ocp_qp_get_D(int stage, struct d_ocp_qp *qp, double *mat); -// -void d_ocp_qp_get_lg(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_lg_mask(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_ug(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_ug_mask(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_Zl(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_Zu(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_zl(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_zu(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_lls(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_lls_mask(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_lus(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_lus_mask(int stage, struct d_ocp_qp *qp, double *vec); -// XXX only valid if there is one slack per softed constraint !!! -void d_ocp_qp_get_idxs(int stage, struct d_ocp_qp *qp, int *vec); -// -void d_ocp_qp_get_idxs_rev(int stage, struct d_ocp_qp *qp, int *vec); -// -//void d_ocp_qp_get_Jsbu(int stage, struct d_ocp_qp *qp, float *vec); -// -//void d_ocp_qp_get_Jsbx(int stage, struct d_ocp_qp *qp, float *vec); -// -//void d_ocp_qp_get_Jsg(int stage, struct d_ocp_qp *qp, float *vec); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_OCP_QP_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_dim.h b/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_dim.h deleted file mode 100644 index dcfb801d31..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_dim.h +++ /dev/null @@ -1,142 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_OCP_QP_DIM_H_ -#define HPIPM_D_OCP_QP_DIM_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_ocp_qp_dim - { - int *nx; // number of states - int *nu; // number of inputs - int *nb; // number of box constraints - int *nbx; // number of state box constraints - int *nbu; // number of input box constraints - int *ng; // number of general constraints - int *ns; // number of soft constraints - int *nsbx; // number of soft state box constraints - int *nsbu; // number of soft input box constraints - int *nsg; // number of soft general constraints - int *nbxe; // number of state box constraints which are equality - int *nbue; // number of input box constraints which are equality - int *nge; // number of general constraints which are equality - int N; // horizon length - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_ocp_qp_dim_strsize(); -// -hpipm_size_t d_ocp_qp_dim_memsize(int N); -// -void d_ocp_qp_dim_create(int N, struct d_ocp_qp_dim *qp_dim, void *memory); -// -void d_ocp_qp_dim_copy_all(struct d_ocp_qp_dim *dim_orig, struct d_ocp_qp_dim *dim_dest); -// -void d_ocp_qp_dim_set_all(int *nx, int *nu, int *nbx, int *nbu, int *ng, int *nsbx, int *nsbu, int *nsg, struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_dim_set(char *field, int stage, int value, struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_dim_set_nx(int stage, int value, struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_dim_set_nu(int stage, int value, struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_dim_set_nbx(int stage, int value, struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_dim_set_nbu(int stage, int value, struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_dim_set_ng(int stage, int value, struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_dim_set_ns(int stage, int value, struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_dim_set_nsbx(int stage, int value, struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_dim_set_nsbu(int stage, int value, struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_dim_set_nsg(int stage, int value, struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_dim_set_nbxe(int stage, int value, struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_dim_set_nbue(int stage, int value, struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_dim_set_nge(int stage, int value, struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_dim_get(struct d_ocp_qp_dim *dim, char *field, int stage, int *value); -// -void d_ocp_qp_dim_get_N(struct d_ocp_qp_dim *dim, int *value); -// -void d_ocp_qp_dim_get_nx(struct d_ocp_qp_dim *dim, int stage, int *value); -// -void d_ocp_qp_dim_get_nu(struct d_ocp_qp_dim *dim, int stage, int *value); -// -void d_ocp_qp_dim_get_nbx(struct d_ocp_qp_dim *dim, int stage, int *value); -// -void d_ocp_qp_dim_get_nbu(struct d_ocp_qp_dim *dim, int stage, int *value); -// -void d_ocp_qp_dim_get_ng(struct d_ocp_qp_dim *dim, int stage, int *value); -// -void d_ocp_qp_dim_get_ns(struct d_ocp_qp_dim *dim, int stage, int *value); -// -void d_ocp_qp_dim_get_nsbx(struct d_ocp_qp_dim *dim, int stage, int *value); -// -void d_ocp_qp_dim_get_nsbu(struct d_ocp_qp_dim *dim, int stage, int *value); -// -void d_ocp_qp_dim_get_nsg(struct d_ocp_qp_dim *dim, int stage, int *value); -// -void d_ocp_qp_dim_get_nbxe(struct d_ocp_qp_dim *dim, int stage, int *value); -// -void d_ocp_qp_dim_get_nbue(struct d_ocp_qp_dim *dim, int stage, int *value); -// -void d_ocp_qp_dim_get_nge(struct d_ocp_qp_dim *dim, int stage, int *value); - - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_OCP_QP_DIM_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_ipm.h b/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_ipm.h deleted file mode 100644 index d2a2833f22..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_ipm.h +++ /dev/null @@ -1,250 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_OCP_QP_IPM_H_ -#define HPIPM_D_OCP_QP_IPM_H_ - - - -#include -#include - -#include -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_ocp_qp_ipm_arg - { - double mu0; // initial value for complementarity slackness - double alpha_min; // exit cond on step length - double res_g_max; // exit cond on inf norm of residuals - double res_b_max; // exit cond on inf norm of residuals - double res_d_max; // exit cond on inf norm of residuals - double res_m_max; // exit cond on inf norm of residuals - double reg_prim; // reg of primal hessian - double lam_min; // min value in lam vector - double t_min; // min value in t vector - double tau_min; // min value of barrier parameter - int iter_max; // exit cond in iter number - int stat_max; // iterations saved in stat - int pred_corr; // use Mehrotra's predictor-corrector IPM algirthm - int cond_pred_corr; // conditional Mehrotra's predictor-corrector - int itref_pred_max; // max number of iterative refinement steps for predictor step - int itref_corr_max; // max number of iterative refinement steps for corrector step - int warm_start; // 0 no warm start, 1 warm start primal sol, 2 warm start primal and dual sol - int square_root_alg; // 0 classical Riccati, 1 square-root Riccati - int lq_fact; // 0 syrk+potrf, 1 mix, 2 lq (for square_root_alg==1) - int abs_form; // absolute IPM formulation - int comp_dual_sol_eq; // dual solution of equality constraints (only for abs_form==1) - int comp_res_exit; // compute residuals on exit (only for abs_form==1 and comp_dual_sol_eq==1) - int comp_res_pred; // compute residuals of prediction - int split_step; // use different steps for primal and dual variables - int var_init_scheme; // variables initialization scheme - int t_lam_min; // clip t and lam: 0 no, 1 in Gamma computation, 2 in solution - int mode; - hpipm_size_t memsize; - }; - - - -struct d_ocp_qp_ipm_ws - { - double qp_res[4]; // infinity norm of residuals - struct d_core_qp_ipm_workspace *core_workspace; - struct d_ocp_qp_dim *dim; // cache dim - struct d_ocp_qp_res_ws *res_workspace; - struct d_ocp_qp_sol *sol_step; - struct d_ocp_qp_sol *sol_itref; - struct d_ocp_qp *qp_step; - struct d_ocp_qp *qp_itref; - struct d_ocp_qp_res *res_itref; - struct d_ocp_qp_res *res; - struct blasfeo_dvec *Gamma; // hessian update - struct blasfeo_dvec *gamma; // hessian update - struct blasfeo_dvec *tmp_nuxM; // work space of size nxM - struct blasfeo_dvec *tmp_nbgM; // work space of size nbM+ngM - struct blasfeo_dvec *tmp_nsM; // work space of size nsM - struct blasfeo_dvec *Pb; // Pb - struct blasfeo_dvec *Zs_inv; - struct blasfeo_dvec *tmp_m; - struct blasfeo_dvec *l; // cache linear part for _get_ric_xxx - struct blasfeo_dmat *L; - struct blasfeo_dmat *Ls; - struct blasfeo_dmat *P; - struct blasfeo_dmat *Lh; - struct blasfeo_dmat *AL; - struct blasfeo_dmat *lq0; - struct blasfeo_dmat *tmp_nxM_nxM; - double *stat; // convergence statistics - int *use_hess_fact; - void *lq_work0; - int iter; // iteration number - int stat_max; // iterations saved in stat - int stat_m; // number of recorded stat per IPM iter - int use_Pb; - int status; // solver status - int square_root_alg; // cache from arg - int lq_fact; // cache from arg - int mask_constr; // use constr mask - int valid_ric_vec; // meaningful riccati vectors - int valid_ric_p; // form of riccati p: 0 p*inv(L), 1 p - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_ocp_qp_ipm_arg_strsize(); -// -hpipm_size_t d_ocp_qp_ipm_arg_memsize(struct d_ocp_qp_dim *ocp_dim); -// -void d_ocp_qp_ipm_arg_create(struct d_ocp_qp_dim *ocp_dim, struct d_ocp_qp_ipm_arg *arg, void *mem); -// -void d_ocp_qp_ipm_arg_set_default(enum hpipm_mode mode, struct d_ocp_qp_ipm_arg *arg); -// -void d_ocp_qp_ipm_arg_set(char *field, void *value, struct d_ocp_qp_ipm_arg *arg); -// set maximum number of iterations -void d_ocp_qp_ipm_arg_set_iter_max(int *iter_max, struct d_ocp_qp_ipm_arg *arg); -// set minimum step lenght -void d_ocp_qp_ipm_arg_set_alpha_min(double *alpha_min, struct d_ocp_qp_ipm_arg *arg); -// set initial value of barrier parameter -void d_ocp_qp_ipm_arg_set_mu0(double *mu0, struct d_ocp_qp_ipm_arg *arg); -// set exit tolerance on stationarity condition -void d_ocp_qp_ipm_arg_set_tol_stat(double *tol_stat, struct d_ocp_qp_ipm_arg *arg); -// set exit tolerance on equality constr -void d_ocp_qp_ipm_arg_set_tol_eq(double *tol_eq, struct d_ocp_qp_ipm_arg *arg); -// set exit tolerance on inequality constr -void d_ocp_qp_ipm_arg_set_tol_ineq(double *tol_ineq, struct d_ocp_qp_ipm_arg *arg); -// set exit tolerance on complementarity condition -void d_ocp_qp_ipm_arg_set_tol_comp(double *tol_comp, struct d_ocp_qp_ipm_arg *arg); -// set regularization of primal variables -void d_ocp_qp_ipm_arg_set_reg_prim(double *tol_comp, struct d_ocp_qp_ipm_arg *arg); -// set warm start: 0 no warm start, 1 primal var -void d_ocp_qp_ipm_arg_set_warm_start(int *warm_start, struct d_ocp_qp_ipm_arg *arg); -// Mehrotra's predictor-corrector IPM algorithm: 0 no predictor-corrector, 1 use predictor-corrector -void d_ocp_qp_ipm_arg_set_pred_corr(int *pred_corr, struct d_ocp_qp_ipm_arg *arg); -// conditional predictor-corrector: 0 no conditinal predictor-corrector, 1 conditional predictor-corrector -void d_ocp_qp_ipm_arg_set_cond_pred_corr(int *value, struct d_ocp_qp_ipm_arg *arg); -// set riccati algorithm: 0 classic, 1 square-root -void d_ocp_qp_ipm_arg_set_ric_alg(int *value, struct d_ocp_qp_ipm_arg *arg); -// dual solution of equality constraints (only for abs_form==1) -void d_ocp_qp_ipm_arg_set_comp_dual_sol_eq(int *value, struct d_ocp_qp_ipm_arg *arg); -// compute residuals after solution -void d_ocp_qp_ipm_arg_set_comp_res_exit(int *value, struct d_ocp_qp_ipm_arg *arg); -// compute residuals of prediction -void d_ocp_qp_ipm_arg_set_comp_res_pred(int *value, struct d_ocp_qp_ipm_arg *arg); -// min value of lam in the solution -void d_ocp_qp_ipm_arg_set_lam_min(double *value, struct d_ocp_qp_ipm_arg *arg); -// min value of t in the solution -void d_ocp_qp_ipm_arg_set_t_min(double *value, struct d_ocp_qp_ipm_arg *arg); -// min value of tau in the solution -void d_ocp_qp_ipm_arg_set_tau_min(double *value, struct d_ocp_qp_ipm_arg *arg); -// set split step: 0 same step, 1 different step for primal and dual variables -void d_ocp_qp_ipm_arg_set_split_step(int *value, struct d_ocp_qp_ipm_arg *arg); -// variables initialization scheme -void d_ocp_qp_ipm_arg_set_var_init_scheme(int *value, struct d_ocp_qp_ipm_arg *arg); -// clip t and lam: 0 no, 1 in Gamma computation, 2 in solution -void d_ocp_qp_ipm_arg_set_t_lam_min(int *value, struct d_ocp_qp_ipm_arg *arg); - -// -hpipm_size_t d_ocp_qp_ipm_ws_strsize(); -// -hpipm_size_t d_ocp_qp_ipm_ws_memsize(struct d_ocp_qp_dim *ocp_dim, struct d_ocp_qp_ipm_arg *arg); -// -void d_ocp_qp_ipm_ws_create(struct d_ocp_qp_dim *ocp_dim, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws, void *mem); -// -void d_ocp_qp_ipm_get(char *field, struct d_ocp_qp_ipm_ws *ws, void *value); -// -void d_ocp_qp_ipm_get_status(struct d_ocp_qp_ipm_ws *ws, int *status); -// -void d_ocp_qp_ipm_get_iter(struct d_ocp_qp_ipm_ws *ws, int *iter); -// -void d_ocp_qp_ipm_get_max_res_stat(struct d_ocp_qp_ipm_ws *ws, double *res_stat); -// -void d_ocp_qp_ipm_get_max_res_eq(struct d_ocp_qp_ipm_ws *ws, double *res_eq); -// -void d_ocp_qp_ipm_get_max_res_ineq(struct d_ocp_qp_ipm_ws *ws, double *res_ineq); -// -void d_ocp_qp_ipm_get_max_res_comp(struct d_ocp_qp_ipm_ws *ws, double *res_comp); -// -void d_ocp_qp_ipm_get_stat(struct d_ocp_qp_ipm_ws *ws, double **stat); -// -void d_ocp_qp_ipm_get_stat_m(struct d_ocp_qp_ipm_ws *ws, int *stat_m); -// -void d_ocp_qp_ipm_get_ric_Lr(struct d_ocp_qp *qp, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws, int stage, double *Lr); -// -void d_ocp_qp_ipm_get_ric_Ls(struct d_ocp_qp *qp, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws, int stage, double *Ls); -// -void d_ocp_qp_ipm_get_ric_P(struct d_ocp_qp *qp, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws, int stage, double *P); -// -void d_ocp_qp_ipm_get_ric_lr(struct d_ocp_qp *qp, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws, int stage, double *lr); -// -void d_ocp_qp_ipm_get_ric_p(struct d_ocp_qp *qp, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws, int stage, double *p); -// feedback control gain in the form u = K x + k -void d_ocp_qp_ipm_get_ric_K(struct d_ocp_qp *qp, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws, int stage, double *K); -// feedback control gain in the form u = K x + k -void d_ocp_qp_ipm_get_ric_k(struct d_ocp_qp *qp, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws, int stage, double *k); -// -void d_ocp_qp_init_var(struct d_ocp_qp *qp, struct d_ocp_qp_sol *qp_sol, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws); -// -void d_ocp_qp_ipm_abs_step(int kk, struct d_ocp_qp *qp, struct d_ocp_qp_sol *qp_sol, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws); -// -void d_ocp_qp_ipm_delta_step(int kk, struct d_ocp_qp *qp, struct d_ocp_qp_sol *qp_sol, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws); -// -void d_ocp_qp_ipm_solve(struct d_ocp_qp *qp, struct d_ocp_qp_sol *qp_sol, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws); -// -void d_ocp_qp_ipm_predict(struct d_ocp_qp *qp, struct d_ocp_qp_sol *qp_sol, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws); -// -void d_ocp_qp_ipm_sens(struct d_ocp_qp *qp, struct d_ocp_qp_sol *qp_sol, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws); - - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_D_OCP_QP_IPM_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_kkt.h b/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_kkt.h deleted file mode 100644 index 19dcec32ca..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_kkt.h +++ /dev/null @@ -1,66 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_OCP_QP_KKT_H_ -#define HPIPM_D_OCP_QP_KKT_H_ - -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - -// -void d_ocp_qp_fact_solve_kkt_unconstr(struct d_ocp_qp *qp, struct d_ocp_qp_sol *qp_sol, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws); -// -void d_ocp_qp_fact_solve_kkt_step(struct d_ocp_qp *qp, struct d_ocp_qp_sol *qp_sol, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws); -// -void d_ocp_qp_fact_lq_solve_kkt_step(struct d_ocp_qp *qp, struct d_ocp_qp_sol *qp_sol, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws); -// -void d_ocp_qp_solve_kkt_step(struct d_ocp_qp *qp, struct d_ocp_qp_sol *qp_sol, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - -#endif // HPIPM_D_OCP_QP_KKT_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_red.h b/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_red.h deleted file mode 100644 index f0482b0444..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_red.h +++ /dev/null @@ -1,117 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_OCP_QP_RED_H_ -#define HPIPM_D_OCP_QP_RED_H_ - - - -#include -#include - -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_ocp_qp_reduce_eq_dof_arg - { - double lam_min; - double t_min; - int alias_unchanged; // do not keep copy unchanged stage - int comp_prim_sol; // primal solution (v) - int comp_dual_sol_eq; // dual solution equality constr (pi) - int comp_dual_sol_ineq; // dual solution inequality constr (lam t) - hpipm_size_t memsize; // memory size in bytes - }; - - - -struct d_ocp_qp_reduce_eq_dof_ws - { - struct blasfeo_dvec *tmp_nuxM; - struct blasfeo_dvec *tmp_nbgM; - int *e_imask_ux; - int *e_imask_d; - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -void d_ocp_qp_dim_reduce_eq_dof(struct d_ocp_qp_dim *dim, struct d_ocp_qp_dim *dim_red); -// -hpipm_size_t d_ocp_qp_reduce_eq_dof_arg_memsize(); -// -void d_ocp_qp_reduce_eq_dof_arg_create(struct d_ocp_qp_reduce_eq_dof_arg *arg, void *mem); -// -void d_ocp_qp_reduce_eq_dof_arg_set_default(struct d_ocp_qp_reduce_eq_dof_arg *arg); -// -void d_ocp_qp_reduce_eq_dof_arg_set_alias_unchanged(struct d_ocp_qp_reduce_eq_dof_arg *arg, int value); -// -void d_ocp_qp_reduce_eq_dof_arg_set_comp_prim_sol(struct d_ocp_qp_reduce_eq_dof_arg *arg, int value); -// -void d_ocp_qp_reduce_eq_dof_arg_set_comp_dual_sol_eq(struct d_ocp_qp_reduce_eq_dof_arg *arg, int value); -// -void d_ocp_qp_reduce_eq_dof_arg_set_comp_dual_sol_ineq(struct d_ocp_qp_reduce_eq_dof_arg *arg, int value); -// -hpipm_size_t d_ocp_qp_reduce_eq_dof_ws_memsize(struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_reduce_eq_dof_ws_create(struct d_ocp_qp_dim *dim, struct d_ocp_qp_reduce_eq_dof_ws *work, void *mem); -// -void d_ocp_qp_reduce_eq_dof(struct d_ocp_qp *qp, struct d_ocp_qp *qp_red, struct d_ocp_qp_reduce_eq_dof_arg *arg, struct d_ocp_qp_reduce_eq_dof_ws *work); -// -void d_ocp_qp_reduce_eq_dof_lhs(struct d_ocp_qp *qp, struct d_ocp_qp *qp_red, struct d_ocp_qp_reduce_eq_dof_arg *arg, struct d_ocp_qp_reduce_eq_dof_ws *work); -// -void d_ocp_qp_reduce_eq_dof_rhs(struct d_ocp_qp *qp, struct d_ocp_qp *qp_red, struct d_ocp_qp_reduce_eq_dof_arg *arg, struct d_ocp_qp_reduce_eq_dof_ws *work); -// -void d_ocp_qp_restore_eq_dof(struct d_ocp_qp *qp, struct d_ocp_qp_sol *qp_sol_red, struct d_ocp_qp_sol *qp_sol, struct d_ocp_qp_reduce_eq_dof_arg *arg, struct d_ocp_qp_reduce_eq_dof_ws *work); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_OCP_QP_RED_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_res.h b/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_res.h deleted file mode 100644 index 061c5729cd..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_res.h +++ /dev/null @@ -1,112 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_OCP_QP_RES_H_ -#define HPIPM_D_OCP_QP_RES_H_ - - - -#include -#include - -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_ocp_qp_res - { - struct d_ocp_qp_dim *dim; - struct blasfeo_dvec *res_g; // q-residuals - struct blasfeo_dvec *res_b; // b-residuals - struct blasfeo_dvec *res_d; // d-residuals - struct blasfeo_dvec *res_m; // m-residuals - double res_max[4]; // max of residuals - double res_mu; // mu-residual - hpipm_size_t memsize; - }; - - - -struct d_ocp_qp_res_ws - { - struct blasfeo_dvec *tmp_nbgM; // work space of size nbM+ngM - struct blasfeo_dvec *tmp_nsM; // work space of size nsM - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_ocp_qp_res_memsize(struct d_ocp_qp_dim *ocp_dim); -// -void d_ocp_qp_res_create(struct d_ocp_qp_dim *ocp_dim, struct d_ocp_qp_res *res, void *mem); -// -hpipm_size_t d_ocp_qp_res_ws_memsize(struct d_ocp_qp_dim *ocp_dim); -// -void d_ocp_qp_res_ws_create(struct d_ocp_qp_dim *ocp_dim, struct d_ocp_qp_res_ws *workspace, void *mem); -// -void d_ocp_qp_res_compute(struct d_ocp_qp *qp, struct d_ocp_qp_sol *qp_sol, struct d_ocp_qp_res *res, struct d_ocp_qp_res_ws *ws); -// -void d_ocp_qp_res_compute_lin(struct d_ocp_qp *qp, struct d_ocp_qp_sol *qp_sol, struct d_ocp_qp_sol *qp_step, struct d_ocp_qp_res *res, struct d_ocp_qp_res_ws *ws); -// -void d_ocp_qp_res_compute_inf_norm(struct d_ocp_qp_res *res); -// -void d_ocp_qp_res_get_all(struct d_ocp_qp_res *res, double **res_r, double **res_q, double **res_ls, double **res_us, double **res_b, double **res_d_lb, double **res_d_ub, double **res_d_lg, double **res_d_ug, double **res_d_ls, double **res_d_us, double **res_m_lb, double **res_m_ub, double **res_m_lg, double **res_m_ug, double **res_m_ls, double **res_m_us); -// -void d_ocp_qp_res_get_max_res_stat(struct d_ocp_qp_res *res, double *value); -// -void d_ocp_qp_res_get_max_res_eq(struct d_ocp_qp_res *res, double *value); -// -void d_ocp_qp_res_get_max_res_ineq(struct d_ocp_qp_res *res, double *value); -// -void d_ocp_qp_res_get_max_res_comp(struct d_ocp_qp_res *res, double *value); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_D_OCP_QP_RES_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_sol.h b/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_sol.h deleted file mode 100644 index eb91f3a7b1..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_sol.h +++ /dev/null @@ -1,128 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_OCP_QP_SOL_H_ -#define HPIPM_D_OCP_QP_SOL_H_ - - - -#include -#include - -#include "hpipm_d_ocp_qp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_ocp_qp_sol - { - struct d_ocp_qp_dim *dim; - struct blasfeo_dvec *ux; - struct blasfeo_dvec *pi; - struct blasfeo_dvec *lam; - struct blasfeo_dvec *t; - void *misc; - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t d_ocp_qp_sol_strsize(); -// -hpipm_size_t d_ocp_qp_sol_memsize(struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_sol_create(struct d_ocp_qp_dim *dim, struct d_ocp_qp_sol *qp_sol, void *memory); -// -void d_ocp_qp_sol_copy_all(struct d_ocp_qp_sol *qp_sol_orig, struct d_ocp_qp_sol *qp_sol_dest); -// -void d_ocp_qp_sol_get_all(struct d_ocp_qp_sol *qp_sol, double **u, double **x, double **ls, double **us, double **pi, double **lam_lb, double **lam_ub, double **lam_lg, double **lam_ug, double **lam_ls, double **lam_us); -// -void d_ocp_qp_sol_get_all_rowmaj(struct d_ocp_qp_sol *qp_sol, double **u, double **x, double **ls, double **us, double **pi, double **lam_lb, double **lam_ub, double **lam_lg, double **lam_ug, double **lam_ls, double **lam_us); -// -void d_ocp_qp_sol_set_all(double **u, double **x, double **ls, double **us, double **pi, double **lam_lb, double **lam_ub, double **lam_lg, double **lam_ug, double **lam_ls, double **lam_us, struct d_ocp_qp_sol *qp_sol); -// -void d_ocp_qp_sol_get(char *field, int stage, struct d_ocp_qp_sol *qp_sol, double *vec); -// -void d_ocp_qp_sol_get_u(int stage, struct d_ocp_qp_sol *qp_sol, double *vec); -// -void d_ocp_qp_sol_get_x(int stage, struct d_ocp_qp_sol *qp_sol, double *vec); -// -void d_ocp_qp_sol_get_sl(int stage, struct d_ocp_qp_sol *qp_sol, double *vec); -// -void d_ocp_qp_sol_get_su(int stage, struct d_ocp_qp_sol *qp_sol, double *vec); -// -void d_ocp_qp_sol_get_pi(int stage, struct d_ocp_qp_sol *qp_sol, double *vec); -// -void d_ocp_qp_sol_get_lam_lb(int stage, struct d_ocp_qp_sol *qp_sol, double *vec); -// -void d_ocp_qp_sol_get_lam_lbu(int stage, struct d_ocp_qp_sol *qp_sol, double *vec); -// -void d_ocp_qp_sol_get_lam_lbx(int stage, struct d_ocp_qp_sol *qp_sol, double *vec); -// -void d_ocp_qp_sol_get_lam_ub(int stage, struct d_ocp_qp_sol *qp_sol, double *vec); -// -void d_ocp_qp_sol_get_lam_ubu(int stage, struct d_ocp_qp_sol *qp_sol, double *vec); -// -void d_ocp_qp_sol_get_lam_ubx(int stage, struct d_ocp_qp_sol *qp_sol, double *vec); -// -void d_ocp_qp_sol_get_lam_lg(int stage, struct d_ocp_qp_sol *qp_sol, double *vec); -// -void d_ocp_qp_sol_get_lam_ug(int stage, struct d_ocp_qp_sol *qp_sol, double *vec); -// -void d_ocp_qp_sol_set(char *field, int stage, double *vec, struct d_ocp_qp_sol *qp_sol); -// -void d_ocp_qp_sol_set_u(int stage, double *vec, struct d_ocp_qp_sol *qp_sol); -// -void d_ocp_qp_sol_set_x(int stage, double *vec, struct d_ocp_qp_sol *qp_sol); -// -void d_ocp_qp_sol_set_sl(int stage, double *vec, struct d_ocp_qp_sol *qp_sol); -// -void d_ocp_qp_sol_set_su(int stage, double *vec, struct d_ocp_qp_sol *qp_sol); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_OCP_QP_SOL_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_utils.h b/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_utils.h deleted file mode 100644 index 217e9d94ae..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_utils.h +++ /dev/null @@ -1,82 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_OCP_QP_UTILS_H_ -#define HPIPM_D_OCP_QP_UTILS_H_ - - - -#include -#include - -#include "hpipm_d_ocp_qp_dim.h" -#include "hpipm_d_ocp_qp.h" -#include "hpipm_d_ocp_qp_sol.h" -#include "hpipm_d_ocp_qp_ipm.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void d_ocp_qp_dim_print(struct d_ocp_qp_dim *qp_dim); -// -void d_ocp_qp_dim_codegen(char *file_name, char *mode, struct d_ocp_qp_dim *qp_dim); -// -void d_ocp_qp_print(struct d_ocp_qp_dim *qp_dim, struct d_ocp_qp *qp); -// -void d_ocp_qp_codegen(char *file_name, char *mode, struct d_ocp_qp_dim *qp_dim, struct d_ocp_qp *qp); -// -void d_ocp_qp_sol_print(struct d_ocp_qp_dim *qp_dim, struct d_ocp_qp_sol *ocp_qp_sol); -// -void d_ocp_qp_ipm_arg_print(struct d_ocp_qp_dim *qp_dim, struct d_ocp_qp_ipm_arg *arg); -// -void d_ocp_qp_ipm_arg_codegen(char *file_name, char *mode, struct d_ocp_qp_dim *qp_dim, struct d_ocp_qp_ipm_arg *arg); -// -void d_ocp_qp_res_print(struct d_ocp_qp_dim *qp_dim, struct d_ocp_qp_res *ocp_qp_res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_OCP_QP_UTILS_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_part_cond.h b/third_party/acados/include/hpipm/include/hpipm_d_part_cond.h deleted file mode 100644 index 1c5f785035..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_part_cond.h +++ /dev/null @@ -1,115 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_D_PART_COND_H_ -#define HPIPM_D_PART_COND_H_ - - - -#include -#include - -#include "hpipm_common.h" -#include "hpipm_d_cond.h" - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_part_cond_qp_arg - { - struct d_cond_qp_arg *cond_arg; - int N2; - hpipm_size_t memsize; - }; - - - -struct d_part_cond_qp_ws - { - struct d_cond_qp_ws *cond_workspace; - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_part_cond_qp_arg_memsize(int N2); -// -void d_part_cond_qp_arg_create(int N2, struct d_part_cond_qp_arg *cond_arg, void *mem); -// -void d_part_cond_qp_arg_set_default(struct d_part_cond_qp_arg *cond_arg); -// set riccati-like algorithm: 0 classical, 1 squre-root -void d_part_cond_qp_arg_set_ric_alg(int ric_alg, struct d_part_cond_qp_arg *cond_arg); -// -void d_part_cond_qp_arg_set_comp_prim_sol(int value, struct d_part_cond_qp_arg *cond_arg); -// -void d_part_cond_qp_arg_set_comp_dual_sol_eq(int value, struct d_part_cond_qp_arg *cond_arg); -// -void d_part_cond_qp_arg_set_comp_dual_sol_ineq(int value, struct d_part_cond_qp_arg *cond_arg); - -// -void d_part_cond_qp_compute_block_size(int N, int N2, int *block_size); -// -void d_part_cond_qp_compute_dim(struct d_ocp_qp_dim *ocp_dim, int *block_size, struct d_ocp_qp_dim *part_dense_dim); -// -hpipm_size_t d_part_cond_qp_ws_memsize(struct d_ocp_qp_dim *ocp_dim, int *block_size, struct d_ocp_qp_dim *part_dense_dim, struct d_part_cond_qp_arg *cond_arg); -// -void d_part_cond_qp_ws_create(struct d_ocp_qp_dim *ocp_dim, int *block_size, struct d_ocp_qp_dim *part_dense_dim, struct d_part_cond_qp_arg *cond_arg, struct d_part_cond_qp_ws *cond_ws, void *mem); -// -void d_part_cond_qp_cond(struct d_ocp_qp *ocp_qp, struct d_ocp_qp *part_dense_qp, struct d_part_cond_qp_arg *cond_arg, struct d_part_cond_qp_ws *cond_ws); -// -void d_part_cond_qp_cond_lhs(struct d_ocp_qp *ocp_qp, struct d_ocp_qp *part_dense_qp, struct d_part_cond_qp_arg *cond_arg, struct d_part_cond_qp_ws *cond_ws); -// -void d_part_cond_qp_cond_rhs(struct d_ocp_qp *ocp_qp, struct d_ocp_qp *part_dense_qp, struct d_part_cond_qp_arg *cond_arg, struct d_part_cond_qp_ws *cond_ws); -// -void d_part_cond_qp_expand_sol(struct d_ocp_qp *ocp_qp, struct d_ocp_qp *part_dense_qp, struct d_ocp_qp_sol *part_dense_qp_sol, struct d_ocp_qp_sol *ocp_qp_sol, struct d_part_cond_qp_arg *cond_arg, struct d_part_cond_qp_ws *cond_ws); - -// -void d_part_cond_qp_update(int *idxc, struct d_ocp_qp *ocp_qp, struct d_ocp_qp *part_dense_qp, struct d_part_cond_qp_arg *cond_arg, struct d_part_cond_qp_ws *cond_ws); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_PART_COND_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_part_cond_qcqp.h b/third_party/acados/include/hpipm/include/hpipm_d_part_cond_qcqp.h deleted file mode 100644 index 2d6624e5bb..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_part_cond_qcqp.h +++ /dev/null @@ -1,106 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_D_PART_COND_QCQP_H_ -#define HPIPM_D_PART_COND_QCQP_H_ - - - -#include -#include - -#include "hpipm_d_cond_qcqp.h" - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_part_cond_qcqp_arg - { - struct d_cond_qcqp_arg *cond_arg; - int N2; - hpipm_size_t memsize; - }; - - - -struct d_part_cond_qcqp_ws - { - struct d_cond_qcqp_ws *cond_ws; - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_part_cond_qcqp_arg_memsize(int N2); -// -void d_part_cond_qcqp_arg_create(int N2, struct d_part_cond_qcqp_arg *cond_arg, void *mem); -// -void d_part_cond_qcqp_arg_set_default(struct d_part_cond_qcqp_arg *cond_arg); -// set riccati-like algorithm: 0 classical, 1 squre-root -void d_part_cond_qcqp_arg_set_ric_alg(int ric_alg, struct d_part_cond_qcqp_arg *cond_arg); - -// -void d_part_cond_qcqp_compute_block_size(int N, int N2, int *block_size); -// -void d_part_cond_qcqp_compute_dim(struct d_ocp_qcqp_dim *ocp_dim, int *block_size, struct d_ocp_qcqp_dim *part_dense_dim); -// -hpipm_size_t d_part_cond_qcqp_ws_memsize(struct d_ocp_qcqp_dim *ocp_dim, int *block_size, struct d_ocp_qcqp_dim *part_dense_dim, struct d_part_cond_qcqp_arg *cond_arg); -// -void d_part_cond_qcqp_ws_create(struct d_ocp_qcqp_dim *ocp_dim, int *block_size, struct d_ocp_qcqp_dim *part_dense_dim, struct d_part_cond_qcqp_arg *cond_arg, struct d_part_cond_qcqp_ws *cond_ws, void *mem); -// -void d_part_cond_qcqp_cond(struct d_ocp_qcqp *ocp_qp, struct d_ocp_qcqp *part_dense_qp, struct d_part_cond_qcqp_arg *cond_arg, struct d_part_cond_qcqp_ws *cond_ws); -// -void d_part_cond_qcqp_cond_lhs(struct d_ocp_qcqp *ocp_qp, struct d_ocp_qcqp *part_dense_qp, struct d_part_cond_qcqp_arg *cond_arg, struct d_part_cond_qcqp_ws *cond_ws); -// -void d_part_cond_qcqp_cond_rhs(struct d_ocp_qcqp *ocp_qp, struct d_ocp_qcqp *part_dense_qp, struct d_part_cond_qcqp_arg *cond_arg, struct d_part_cond_qcqp_ws *cond_ws); -// -void d_part_cond_qcqp_expand_sol(struct d_ocp_qcqp *ocp_qp, struct d_ocp_qcqp *part_dense_qp, struct d_ocp_qcqp_sol *part_dense_qp_sol, struct d_ocp_qcqp_sol *ocp_qp_sol, struct d_part_cond_qcqp_arg *cond_arg, struct d_part_cond_qcqp_ws *cond_ws); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_PART_COND_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_sim_erk.h b/third_party/acados/include/hpipm/include/hpipm_d_sim_erk.h deleted file mode 100644 index 320b66bb28..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_sim_erk.h +++ /dev/null @@ -1,122 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_SIM_ERK_H_ -#define HPIPM_D_SIM_ERK_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - -struct d_sim_erk_arg - { - struct d_sim_rk_data *rk_data; // integrator data - double h; // step size - int steps; // number of steps -// int for_sens; // compute adjoint sensitivities -// int adj_sens; // compute adjoint sensitivities - hpipm_size_t memsize; - }; - - - -struct d_sim_erk_ws - { - void (*ode)(int t, double *x, double *p, void *ode_args, double *xdot); // function pointer to ode - void (*vde_for)(int t, double *x, double *p, void *ode_args, double *xdot); // function pointer to forward vde - void (*vde_adj)(int t, double *adj_in, void *ode_args, double *adj_out); // function pointer to adjoint vde - void *ode_args; // pointer to ode args - struct d_sim_erk_arg *erk_arg; // erk arg - double *K; // internal variables - double *x_for; // states and forward sensitivities - double *x_traj; // states at all steps - double *l; // adjoint sensitivities - double *p; // parameter - double *x_tmp; // temporary states and forward sensitivities - double *adj_in; - double *adj_tmp; - int nx; // number of states - int np; // number of parameters - int nf; // number of forward sensitivities - int na; // number of adjoint sensitivities - int nf_max; // max number of forward sensitivities - int na_max; // max number of adjoint sensitivities - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_sim_erk_arg_memsize(); -// -void d_sim_erk_arg_create(struct d_sim_erk_arg *erk_arg, void *mem); -// -void d_sim_erk_arg_set_all(struct d_sim_rk_data *rk_data, double h, int steps, struct d_sim_erk_arg *erk_arg); - -// -hpipm_size_t d_sim_erk_ws_memsize(struct d_sim_erk_arg *erk_arg, int nx, int np, int nf_max, int na_max); -// -void d_sim_erk_ws_create(struct d_sim_erk_arg *erk_arg, int nx, int np, int nf_max, int na_max, struct d_sim_erk_ws *work, void *memory); -// -void d_sim_erk_ws_set_all(int nf, int na, double *x, double *fs, double *bs, double *p, void (*ode)(int t, double *x, double *p, void *ode_args, double *xdot), void (*vde_for)(int t, double *x, double *p, void *ode_args, double *xdot), void (*vde_adj)(int t, double *adj_in, void *ode_args, double *adj_out), void *ode_args, struct d_sim_erk_ws *work); -// number of directions for forward sensitivities -void d_sim_erk_ws_set_nf(int *nf, struct d_sim_erk_ws *work); -// parameters (e.g. inputs) -void d_sim_erk_ws_set_p(double *p, struct d_sim_erk_ws *work); -// state -void d_sim_erk_ws_set_x(double *x, struct d_sim_erk_ws *work); -// forward sensitivities -void d_sim_erk_ws_set_fs(double *fs, struct d_sim_erk_ws *work); -// ode funtion -void d_sim_erk_ws_set_ode(void (*ode)(int t, double *x, double *p, void *ode_args, double *xdot), struct d_sim_erk_ws *work); -// forward vde function -void d_sim_erk_ws_set_vde_for(void (*ode)(int t, double *x, double *p, void *ode_args, double *xdot), struct d_sim_erk_ws *work); -// ode_args, passed straight to the ode/vde_for/vde_adj functions -void d_sim_erk_ws_set_ode_args(void *ode_args, struct d_sim_erk_ws *work); -// state -void d_sim_erk_ws_get_x(struct d_sim_erk_ws *work, double *x); -// forward sensitivities -void d_sim_erk_ws_get_fs(struct d_sim_erk_ws *work, double *fs); -// -void d_sim_erk_solve(struct d_sim_erk_arg *arg, struct d_sim_erk_ws *work); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // HPIPM_D_SIM_ERK_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_sim_rk.h b/third_party/acados/include/hpipm/include/hpipm_d_sim_rk.h deleted file mode 100644 index a50dcbb491..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_sim_rk.h +++ /dev/null @@ -1,71 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_SIM_RK_H_ -#define HPIPM_D_SIM_RK_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - -struct d_sim_rk_data - { - double *A_rk; // A in butcher tableau - double *B_rk; // b in butcher tableau - double *C_rk; // c in butcher tableau - int expl; // erk vs irk - int ns; // number of stages - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_sim_rk_data_memsize(int ns); -// -void d_sim_rk_data_create(int ns, struct d_sim_rk_data *rk_data, void *memory); -// -void d_sim_rk_data_init_default(char *field, struct d_sim_rk_data *rk_data); -// -void d_sim_rk_data_set_all(int expl, double *A_rk, double *B_rk, double *C_rk, struct d_sim_rk_data *rk_data); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // HPIPM_D_SIM_RK_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp.h b/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp.h deleted file mode 100644 index f36b51a064..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp.h +++ /dev/null @@ -1,213 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_TREE_OCP_QCQP_H_ -#define HPIPM_D_TREE_OCP_QCQP_H_ - - - -#include -#include - -#include "hpipm_common.h" -#include "hpipm_d_tree_ocp_qcqp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_tree_ocp_qcqp - { - struct d_tree_ocp_qcqp_dim *dim; - struct blasfeo_dmat *BAbt; // Nn-1 - struct blasfeo_dmat *RSQrq; // Nn - struct blasfeo_dmat *DCt; // Nn - struct blasfeo_dmat **Hq; // Nn - struct blasfeo_dvec *b; // Nn-1 - struct blasfeo_dvec *rqz; // Nn - struct blasfeo_dvec *d; // Nn - struct blasfeo_dvec *d_mask; // Nn - struct blasfeo_dvec *m; // Nn - struct blasfeo_dvec *Z; // Nn - int **idxb; // indices of box constrained variables within [u; x] // Nn - int **idxs_rev; // index of soft constraints - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t d_tree_ocp_qcqp_memsize(struct d_tree_ocp_qcqp_dim *dim); -// -void d_tree_ocp_qcqp_create(struct d_tree_ocp_qcqp_dim *dim, struct d_tree_ocp_qcqp *qp, void *memory); -// -void d_tree_ocp_qcqp_set_all(double **A, double **B, double **b, double **Q, double **S, double **R, double **q, double **r, int **idxb, double **d_lb, double **d_ub, double **C, double **D, double **d_lg, double **d_ug, double **Zl, double **Zu, double **zl, double **zu, int **idxs, double **d_ls, double **d_us, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set(char *field_name, int node_edge, void *value, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_A(int edge, double *mat, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_B(int edge, double *mat, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_b(int edge, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_Q(int node, double *mat, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_S(int node, double *mat, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_R(int node, double *mat, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_q(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_r(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_lb(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_lb_mask(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_ub(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_ub_mask(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_lbx(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_lbx_mask(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_ubx(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_ubx_mask(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_lbu(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_lbu_mask(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_ubu(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_ubu_mask(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_idxb(int node, int *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_idxbx(int node, int *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_Jbx(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_idxbu(int node, int *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_Jbu(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_C(int node, double *mat, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_D(int node, double *mat, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_lg(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_lg_mask(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_ug(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_ug_mask(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_Qq(int node, double *mat, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_Sq(int node, double *mat, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_Rq(int node, double *mat, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_qq(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_rq(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_uq(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_uq_mask(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_Zl(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_Zu(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_zl(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_zu(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_lls(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_lls_mask(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_lus(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_lus_mask(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_idxs(int node, int *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_idxs_rev(int node, int *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_Jsbu(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_Jsbx(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_Jsg(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_Jsq(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -//void d_tree_ocp_qcqp_set_idxe(int node, int *vec, struct d_tree_ocp_qcqp *qp); -// -//void d_tree_ocp_qcqp_set_idxbxe(int node, int *vec, struct d_tree_ocp_qcqp *qp); -// -//void d_tree_ocp_qcqp_set_idxbue(int node, int *vec, struct d_tree_ocp_qcqp *qp); -// -//void d_tree_ocp_qcqp_set_idxge(int node, int *vec, struct d_tree_ocp_qcqp *qp); -// -//void d_tree_ocp_qcqp_set_Jbxe(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -//void d_tree_ocp_qcqp_set_Jbue(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -//void d_tree_ocp_qcqp_set_Jge(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -//void d_tree_ocp_qcqp_set_diag_H_flag(int node, int *value, struct d_tree_ocp_qcqp *qp); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_TREE_OCP_QCQP_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_dim.h b/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_dim.h deleted file mode 100644 index 257b82b252..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_dim.h +++ /dev/null @@ -1,117 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_TREE_OCP_QCQP_DIM_H_ -#define HPIPM_D_TREE_OCP_QCQP_DIM_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_tree_ocp_qcqp_dim - { - struct d_tree_ocp_qp_dim *qp_dim; // dim of qp approximation - struct tree *ttree; // tree describing node conndection - int *nx; // number of states // Nn - int *nu; // number of inputs // Nn - int *nb; // number of box constraints // Nn - int *nbx; // number of state box constraints // Nn - int *nbu; // number of input box constraints // Nn - int *ng; // number of general constraints // Nn - int *nq; // number of (upper) quadratic constraints - int *ns; // number of soft constraints // Nn - int *nsbx; // number of soft state box constraints - int *nsbu; // number of soft input box constraints - int *nsg; // number of soft general constraints - int *nsq; // number of (upper) soft quadratic constraints - int Nn; // number of nodes - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_tree_ocp_qcqp_dim_strsize(); -// -hpipm_size_t d_tree_ocp_qcqp_dim_memsize(int Nn); -// -void d_tree_ocp_qcqp_dim_create(int Nn, struct d_tree_ocp_qcqp_dim *qp_dim, void *memory); -// -void d_tree_ocp_qcqp_dim_set_tree(struct tree *ttree, struct d_tree_ocp_qcqp_dim *dim); -// -void d_tree_ocp_qcqp_dim_set(char *field, int stage, int value, struct d_tree_ocp_qcqp_dim *dim); -// -void d_tree_ocp_qcqp_dim_set_nx(int stage, int value, struct d_tree_ocp_qcqp_dim *dim); -// -void d_tree_ocp_qcqp_dim_set_nu(int stage, int value, struct d_tree_ocp_qcqp_dim *dim); -// -void d_tree_ocp_qcqp_dim_set_nbx(int stage, int value, struct d_tree_ocp_qcqp_dim *dim); -// -void d_tree_ocp_qcqp_dim_set_nbu(int stage, int value, struct d_tree_ocp_qcqp_dim *dim); -// -void d_tree_ocp_qcqp_dim_set_ng(int stage, int value, struct d_tree_ocp_qcqp_dim *dim); -// -void d_tree_ocp_qcqp_dim_set_nq(int stage, int value, struct d_tree_ocp_qcqp_dim *dim); -// -void d_tree_ocp_qcqp_dim_set_ns(int stage, int value, struct d_tree_ocp_qcqp_dim *dim); -// -void d_tree_ocp_qcqp_dim_set_nsbx(int stage, int value, struct d_tree_ocp_qcqp_dim *dim); -// -void d_tree_ocp_qcqp_dim_set_nsbu(int stage, int value, struct d_tree_ocp_qcqp_dim *dim); -// -void d_tree_ocp_qcqp_dim_set_nsg(int stage, int value, struct d_tree_ocp_qcqp_dim *dim); -// -void d_tree_ocp_qcqp_dim_set_nsq(int stage, int value, struct d_tree_ocp_qcqp_dim *dim); -// -//void d_tree_ocp_qcqp_dim_set_nbxe(int stage, int value, struct d_tree_ocp_qcqp_dim *dim); -// -//void d_tree_ocp_qcqp_dim_set_nbue(int stage, int value, struct d_tree_ocp_qcqp_dim *dim); -// -//void d_tree_ocp_qcqp_dim_set_nge(int stage, int value, struct d_tree_ocp_qcqp_dim *dim); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_TREE_OCP_QCQP_DIM_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_ipm.h b/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_ipm.h deleted file mode 100644 index 4a0fed1067..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_ipm.h +++ /dev/null @@ -1,191 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_TREE_OCP_QCQP_IPM_H_ -#define HPIPM_D_TREE_OCP_QCQP_IPM_H_ - - - -#include -#include - -#include -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_tree_ocp_qcqp_ipm_arg - { - struct d_tree_ocp_qp_ipm_arg *qp_arg; - double mu0; // initial value for complementarity slackness - double alpha_min; // exit cond on step length - double res_g_max; // exit cond on inf norm of residuals - double res_b_max; // exit cond on inf norm of residuals - double res_d_max; // exit cond on inf norm of residuals - double res_m_max; // exit cond on inf norm of residuals - double reg_prim; // reg of primal hessian - double lam_min; // min value in lam vector - double t_min; // min value in t vector - int iter_max; // exit cond in iter number - int stat_max; // iterations saved in stat - int pred_corr; // use Mehrotra's predictor-corrector IPM algirthm - int cond_pred_corr; // conditional Mehrotra's predictor-corrector - int itref_pred_max; // max number of iterative refinement steps for predictor step - int itref_corr_max; // max number of iterative refinement steps for corrector step - int warm_start; // 0 no warm start, 1 warm start primal sol, 2 warm start primal and dual sol -// int square_root_alg; // 0 classical Riccati, 1 square-root Riccati - int lq_fact; // 0 syrk+potrf, 1 mix, 2 lq (for square_root_alg==1) - int abs_form; // absolute IPM formulation - int comp_dual_sol_eq; // dual solution of equality constrains (only for abs_form==1) - int comp_res_exit; // compute residuals on exit (only for abs_form==1 and comp_dual_sol_eq==1) -// int comp_res_pred; // compute residuals of prediction - int split_step; // use different step for primal and dual variables - int t_lam_min; // clip t and lam: 0 no, 1 in Gamma computation, 2 in solution - int mode; - hpipm_size_t memsize; - }; - - - -struct d_tree_ocp_qcqp_ipm_ws - { - struct d_tree_ocp_qp_ipm_ws *qp_ws; - struct d_tree_ocp_qp *qp; - struct d_tree_ocp_qp_sol *qp_sol; - struct d_tree_ocp_qcqp_res_ws *qcqp_res_ws; - struct d_tree_ocp_qcqp_res *qcqp_res; - struct blasfeo_dvec *tmp_nuxM; - int iter; // iteration number - int status; - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_tree_ocp_qcqp_ipm_arg_strsize(); -// -hpipm_size_t d_tree_ocp_qcqp_ipm_arg_memsize(struct d_tree_ocp_qcqp_dim *ocp_dim); -// -void d_tree_ocp_qcqp_ipm_arg_create(struct d_tree_ocp_qcqp_dim *ocp_dim, struct d_tree_ocp_qcqp_ipm_arg *arg, void *mem); -// -void d_tree_ocp_qcqp_ipm_arg_set_default(enum hpipm_mode mode, struct d_tree_ocp_qcqp_ipm_arg *arg); -// -void d_tree_ocp_qcqp_ipm_arg_set(char *field, void *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// set maximum number of iterations -void d_tree_ocp_qcqp_ipm_arg_set_iter_max(int *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// set minimum step lenght -void d_tree_ocp_qcqp_ipm_arg_set_alpha_min(double *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// set initial value of barrier parameter -void d_tree_ocp_qcqp_ipm_arg_set_mu0(double *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on stationarity condition -void d_tree_ocp_qcqp_ipm_arg_set_tol_stat(double *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on equality constr -void d_tree_ocp_qcqp_ipm_arg_set_tol_eq(double *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on inequality constr -void d_tree_ocp_qcqp_ipm_arg_set_tol_ineq(double *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on complementarity condition -void d_tree_ocp_qcqp_ipm_arg_set_tol_comp(double *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// set regularization of primal variables -void d_tree_ocp_qcqp_ipm_arg_set_reg_prim(double *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// set warm start: 0 no warm start, 1 primal var -void d_tree_ocp_qcqp_ipm_arg_set_warm_start(int *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// Mehrotra's predictor-corrector IPM algorithm: 0 no predictor-corrector, 1 use predictor-corrector -void d_tree_ocp_qcqp_ipm_arg_set_pred_corr(int *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// conditional predictor-corrector: 0 no conditinal predictor-corrector, 1 conditional predictor-corrector -void d_tree_ocp_qcqp_ipm_arg_set_cond_pred_corr(int *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// set riccati algorithm: 0 classic, 1 square-root -//void d_tree_ocp_qcqp_ipm_arg_set_ric_alg(int *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// compute residuals after solution -void d_tree_ocp_qcqp_ipm_arg_set_comp_res_exit(int *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// compute residuals of prediction -//void d_tree_ocp_qcqp_ipm_arg_set_comp_res_pred(int *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// min value of lam in the solution -void d_tree_ocp_qcqp_ipm_arg_set_lam_min(double *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// min value of t in the solution -void d_tree_ocp_qcqp_ipm_arg_set_t_min(double *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// use different step for primal and dual variables -void d_tree_ocp_qcqp_ipm_arg_set_split_step(int *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// clip t and lam: 0 no, 1 in Gamma computation, 2 in solution -void d_tree_ocp_qcqp_ipm_arg_set_t_lam_min(int *value, struct d_tree_ocp_qcqp_ipm_arg *arg); - -// -hpipm_size_t d_tree_ocp_qcqp_ipm_ws_strsize(); -// -hpipm_size_t d_tree_ocp_qcqp_ipm_ws_memsize(struct d_tree_ocp_qcqp_dim *ocp_dim, struct d_tree_ocp_qcqp_ipm_arg *arg); -// -void d_tree_ocp_qcqp_ipm_ws_create(struct d_tree_ocp_qcqp_dim *ocp_dim, struct d_tree_ocp_qcqp_ipm_arg *arg, struct d_tree_ocp_qcqp_ipm_ws *ws, void *mem); -// -void d_tree_ocp_qcqp_ipm_get(char *field, struct d_tree_ocp_qcqp_ipm_ws *ws, void *value); -// -void d_tree_ocp_qcqp_ipm_get_status(struct d_tree_ocp_qcqp_ipm_ws *ws, int *status); -// -void d_tree_ocp_qcqp_ipm_get_iter(struct d_tree_ocp_qcqp_ipm_ws *ws, int *iter); -// -void d_tree_ocp_qcqp_ipm_get_max_res_stat(struct d_tree_ocp_qcqp_ipm_ws *ws, double *res_stat); -// -void d_tree_ocp_qcqp_ipm_get_max_res_eq(struct d_tree_ocp_qcqp_ipm_ws *ws, double *res_eq); -// -void d_tree_ocp_qcqp_ipm_get_max_res_ineq(struct d_tree_ocp_qcqp_ipm_ws *ws, double *res_ineq); -// -void d_tree_ocp_qcqp_ipm_get_max_res_comp(struct d_tree_ocp_qcqp_ipm_ws *ws, double *res_comp); -// -void d_tree_ocp_qcqp_ipm_get_stat(struct d_tree_ocp_qcqp_ipm_ws *ws, double **stat); -// -void d_tree_ocp_qcqp_ipm_get_stat_m(struct d_tree_ocp_qcqp_ipm_ws *ws, int *stat_m); -// -void d_tree_ocp_qcqp_init_var(struct d_tree_ocp_qcqp *qp, struct d_tree_ocp_qcqp_sol *qp_sol, struct d_tree_ocp_qcqp_ipm_arg *arg, struct d_tree_ocp_qcqp_ipm_ws *ws); -// -void d_tree_ocp_qcqp_ipm_solve(struct d_tree_ocp_qcqp *qp, struct d_tree_ocp_qcqp_sol *qp_sol, struct d_tree_ocp_qcqp_ipm_arg *arg, struct d_tree_ocp_qcqp_ipm_ws *ws); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_D_TREE_OCP_QCQP_IPM_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_res.h b/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_res.h deleted file mode 100644 index 69eebb1ba4..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_res.h +++ /dev/null @@ -1,108 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_TREE_OCP_QCQP_RES_H_ -#define HPIPM_D_TREE_OCP_QCQP_RES_H_ - - - -#include -#include - -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_tree_ocp_qcqp_res - { - struct d_tree_ocp_qcqp_dim *dim; - struct blasfeo_dvec *res_g; // q-residuals - struct blasfeo_dvec *res_b; // b-residuals - struct blasfeo_dvec *res_d; // d-residuals - struct blasfeo_dvec *res_m; // m-residuals - double res_max[4]; // max of residuals - double res_mu; // mu-residual - hpipm_size_t memsize; - }; - - - -struct d_tree_ocp_qcqp_res_ws - { - struct blasfeo_dvec *tmp_nuxM; // work space of size nuM+nxM - struct blasfeo_dvec *tmp_nbgqM; // work space of size nbM+ngM+nqM - struct blasfeo_dvec *tmp_nsM; // work space of size nsM - struct blasfeo_dvec *q_fun; // value for evaluation of quadr constr - struct blasfeo_dvec *q_adj; // value for adjoint of quadr constr - int use_q_fun; // reuse cached value for evaluation of quadr constr - int use_q_adj; // reuse cached value for adjoint of quadr constr - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_tree_ocp_qcqp_res_memsize(struct d_tree_ocp_qcqp_dim *ocp_dim); -// -void d_tree_ocp_qcqp_res_create(struct d_tree_ocp_qcqp_dim *ocp_dim, struct d_tree_ocp_qcqp_res *res, void *mem); -// -hpipm_size_t d_tree_ocp_qcqp_res_ws_memsize(struct d_tree_ocp_qcqp_dim *ocp_dim); -// -void d_tree_ocp_qcqp_res_ws_create(struct d_tree_ocp_qcqp_dim *ocp_dim, struct d_tree_ocp_qcqp_res_ws *ws, void *mem); -// -void d_tree_ocp_qcqp_res_compute(struct d_tree_ocp_qcqp *qp, struct d_tree_ocp_qcqp_sol *qp_sol, struct d_tree_ocp_qcqp_res *res, struct d_tree_ocp_qcqp_res_ws *ws); -// -void d_tree_ocp_qcqp_res_compute_inf_norm(struct d_tree_ocp_qcqp_res *res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_D_TREE_OCP_QCQP_RES_H_ - - - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_sol.h b/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_sol.h deleted file mode 100644 index cde8de5c51..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_sol.h +++ /dev/null @@ -1,99 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_TREE_OCP_QCQP_SOL_H_ -#define HPIPM_D_TREE_OCP_QCQP_SOL_H_ - - - -#include -#include - -#include "hpipm_d_tree_ocp_qcqp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - -struct d_tree_ocp_qcqp_sol - { - struct d_tree_ocp_qcqp_dim *dim; - struct blasfeo_dvec *ux; - struct blasfeo_dvec *pi; - struct blasfeo_dvec *lam; - struct blasfeo_dvec *t; - void *misc; - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t d_tree_ocp_qcqp_sol_memsize(struct d_tree_ocp_qcqp_dim *dim); -// -void d_tree_ocp_qcqp_sol_create(struct d_tree_ocp_qcqp_dim *dim, struct d_tree_ocp_qcqp_sol *qp_sol, void *memory); -// -void d_tree_ocp_qcqp_sol_get(char *field, int node_edge, struct d_tree_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qcqp_sol_get_u(int node, struct d_tree_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qcqp_sol_get_x(int node, struct d_tree_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qcqp_sol_get_sl(int node, struct d_tree_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qcqp_sol_get_su(int node, struct d_tree_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qcqp_sol_get_pi(int edge, struct d_tree_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qcqp_sol_get_lam_lb(int node, struct d_tree_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qcqp_sol_get_lam_ub(int node, struct d_tree_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qcqp_sol_get_lam_lg(int node, struct d_tree_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qcqp_sol_get_lam_ug(int node, struct d_tree_ocp_qcqp_sol *qp_sol, double *vec); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_TREE_OCP_QCQP_SOL_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_utils.h b/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_utils.h deleted file mode 100644 index 5ef04fcf66..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_utils.h +++ /dev/null @@ -1,84 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_TREE_OCP_QP_UTILS_H_ -#define HPIPM_D_TREE_OCP_QP_UTILS_H_ - - - -#include -#include - -#include "hpipm_d_tree_ocp_qcqp_dim.h" -#include "hpipm_d_tree_ocp_qcqp.h" -#include "hpipm_d_tree_ocp_qcqp_sol.h" -#include "hpipm_d_tree_ocp_qcqp_ipm.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void d_tree_ocp_qcqp_dim_print(struct d_tree_ocp_qcqp_dim *qp_dim); -// -//void d_tree_ocp_qcqp_dim_codegen(char *file_name, char *mode, struct d_tree_ocp_qcqp_dim *qp_dim); -// -void d_tree_ocp_qcqp_print(struct d_tree_ocp_qcqp_dim *qp_dim, struct d_tree_ocp_qcqp *qp); -// -//void d_tree_ocp_qcqp_codegen(char *file_name, char *mode, struct d_tree_ocp_qcqp_dim *qp_dim, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_sol_print(struct d_tree_ocp_qcqp_dim *qp_dim, struct d_tree_ocp_qcqp_sol *ocp_qcqp_sol); -// -void d_tree_ocp_qcqp_ipm_arg_print(struct d_tree_ocp_qcqp_dim *qp_dim, struct d_tree_ocp_qcqp_ipm_arg *arg); -// -//void d_tree_ocp_qcqp_ipm_arg_codegen(char *file_name, char *mode, struct d_tree_ocp_qcqp_dim *qp_dim, struct d_tree_ocp_qcqp_ipm_arg *arg); -// -void d_tree_ocp_qcqp_res_print(struct d_tree_ocp_qcqp_dim *qp_dim, struct d_tree_ocp_qcqp_res *ocp_qcqp_res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_TREE_OCP_QP_UTILS_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp.h b/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp.h deleted file mode 100644 index 1666ad7c71..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp.h +++ /dev/null @@ -1,195 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_TREE_OCP_QP_H_ -#define HPIPM_D_TREE_OCP_QP_H_ - - - -#include -#include - -#include "hpipm_d_tree_ocp_qp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_tree_ocp_qp - { - struct d_tree_ocp_qp_dim *dim; - struct blasfeo_dmat *BAbt; // Nn-1 - struct blasfeo_dmat *RSQrq; // Nn - struct blasfeo_dmat *DCt; // Nn - struct blasfeo_dvec *b; // Nn-1 - struct blasfeo_dvec *rqz; // Nn - struct blasfeo_dvec *d; // Nn - struct blasfeo_dvec *d_mask; // Nn - struct blasfeo_dvec *m; // Nn - struct blasfeo_dvec *Z; // Nn - int **idxb; // indices of box constrained variables within [u; x] // Nn -// int **idxs; // index of soft constraints - int **idxs_rev; // index of soft constraints - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t d_tree_ocp_qp_memsize(struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_create(struct d_tree_ocp_qp_dim *dim, struct d_tree_ocp_qp *qp, void *memory); -// -void d_tree_ocp_qp_set_all(double **A, double **B, double **b, double **Q, double **S, double **R, double **q, double **r, int **idxb, double **d_lb, double **d_ub, double **C, double **D, double **d_lg, double **d_ug, double **Zl, double **Zu, double **zl, double **zu, int **idxs, double **d_ls, double **d_us, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set(char *field_name, int node_edge, void *value, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_A(int edge, double *mat, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_B(int edge, double *mat, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_b(int edge, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_Q(int node, double *mat, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_S(int node, double *mat, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_R(int node, double *mat, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_q(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_r(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_lb(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_lb_mask(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_ub(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_ub_mask(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_lbx(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_lbx_mask(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_ubx(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_ubx_mask(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_lbu(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_lbu_mask(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_ubu(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_ubu_mask(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_idxb(int node, int *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_idxbx(int node, int *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_Jbx(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_idxbu(int node, int *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_Jbu(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_C(int node, double *mat, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_D(int node, double *mat, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_lg(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_lg_mask(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_ug(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_ug_mask(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_Zl(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_Zu(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_zl(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_zu(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_lls(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_lls_mask(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_lus(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_lus_mask(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_idxs(int node, int *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_idxs_rev(int node, int *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_Jsbu(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_Jsbx(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_Jsg(int node, double *vec, struct d_tree_ocp_qp *qp); -// -//void d_tree_ocp_qp_set_idxe(int node, int *vec, struct d_tree_ocp_qp *qp); -// -//void d_tree_ocp_qp_set_idxbxe(int node, int *vec, struct d_tree_ocp_qp *qp); -// -//void d_tree_ocp_qp_set_idxbue(int node, int *vec, struct d_tree_ocp_qp *qp); -// -//void d_tree_ocp_qp_set_idxge(int node, int *vec, struct d_tree_ocp_qp *qp); -// -//void d_tree_ocp_qp_set_Jbxe(int node, double *vec, struct d_tree_ocp_qp *qp); -// -//void d_tree_ocp_qp_set_Jbue(int node, double *vec, struct d_tree_ocp_qp *qp); -// -//void d_tree_ocp_qp_set_Jge(int node, double *vec, struct d_tree_ocp_qp *qp); -// -//void d_tree_ocp_qp_set_diag_H_flag(int node, int *value, struct d_tree_ocp_qp *qp); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_TREE_OCP_QP_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_dim.h b/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_dim.h deleted file mode 100644 index 659b664594..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_dim.h +++ /dev/null @@ -1,111 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_TREE_OCP_QP_DIM_H_ -#define HPIPM_D_TREE_OCP_QP_DIM_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_tree_ocp_qp_dim - { - struct tree *ttree; // tree describing node conndection - int *nx; // number of states // Nn - int *nu; // number of inputs // Nn - int *nb; // number of box constraints // Nn - int *nbx; // number of state box constraints // Nn - int *nbu; // number of input box constraints // Nn - int *ng; // number of general constraints // Nn - int *ns; // number of soft constraints // Nn - int *nsbx; // number of soft state box constraints - int *nsbu; // number of soft input box constraints - int *nsg; // number of soft general constraints - int Nn; // number of nodes - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_tree_ocp_qp_dim_strsize(); -// -hpipm_size_t d_tree_ocp_qp_dim_memsize(int Nn); -// -void d_tree_ocp_qp_dim_create(int Nn, struct d_tree_ocp_qp_dim *qp_dim, void *memory); -// -void d_tree_ocp_qp_dim_set_all(struct tree *ttree, int *nx, int *nu, int *nbx, int *nbu, int *ng, int *nsbx, int *nsbu, int *nsg, struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_dim_set_tree(struct tree *ttree, struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_dim_set(char *field, int stage, int value, struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_dim_set_nx(int stage, int value, struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_dim_set_nu(int stage, int value, struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_dim_set_nbx(int stage, int value, struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_dim_set_nbu(int stage, int value, struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_dim_set_ng(int stage, int value, struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_dim_set_ns(int stage, int value, struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_dim_set_nsbx(int stage, int value, struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_dim_set_nsbu(int stage, int value, struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_dim_set_nsg(int stage, int value, struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_dim_set_nbxe(int stage, int value, struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_dim_set_nbue(int stage, int value, struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_dim_set_nge(int stage, int value, struct d_tree_ocp_qp_dim *dim); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_TREE_OCP_QP_DIM_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_ipm.h b/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_ipm.h deleted file mode 100644 index fb634208ce..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_ipm.h +++ /dev/null @@ -1,209 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_D_TREE_OCP_QP_IPM_H_ -#define HPIPM_D_TREE_OCP_QP_IPM_H_ - - - -#include -#include - -#include -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_tree_ocp_qp_ipm_arg - { - double mu0; // initial value for duality measure - double alpha_min; // exit cond on step length - double res_g_max; // exit cond on inf norm of residuals - double res_b_max; // exit cond on inf norm of residuals - double res_d_max; // exit cond on inf norm of residuals - double res_m_max; // exit cond on inf norm of residuals - double reg_prim; // reg of primal hessian - double lam_min; // min value in lam vector - double t_min; // min value in t vector - double tau_min; // min value of barrier parameter - int iter_max; // exit cond in iter number - int stat_max; // iterations saved in stat - int pred_corr; // use Mehrotra's predictor-corrector IPM algirthm - int cond_pred_corr; // conditional Mehrotra's predictor-corrector - int itref_pred_max; // max number of iterative refinement steps for predictor step - int itref_corr_max; // max number of iterative refinement steps for corrector step - int warm_start; // 0 no warm start, 1 warm start primal sol, 2 warm start primal and dual sol - int lq_fact; // 0 syrk+potrf, 1 mix, 2 lq - int abs_form; // absolute IPM formulation - int comp_dual_sol_eq; // dual solution (only for abs_form==1) - int comp_res_exit; // compute residuals on exit (only for abs_form==1 and comp_dual_sol==1) - int split_step; // use different steps for primal and dual variables - int t_lam_min; // clip t and lam: 0 no, 1 in Gamma computation, 2 in solution - int mode; - hpipm_size_t memsize; - }; - - - -struct d_tree_ocp_qp_ipm_ws - { - struct d_core_qp_ipm_workspace *core_workspace; - struct d_tree_ocp_qp_res_ws *res_workspace; - struct d_tree_ocp_qp_sol *sol_step; - struct d_tree_ocp_qp_sol *sol_itref; - struct d_tree_ocp_qp *qp_step; - struct d_tree_ocp_qp *qp_itref; - struct d_tree_ocp_qp_res *res_itref; - struct d_tree_ocp_qp_res *res; - struct blasfeo_dvec *Gamma; // hessian update - struct blasfeo_dvec *gamma; // hessian update - struct blasfeo_dvec *tmp_nxM; // work space of size nxM - struct blasfeo_dvec *tmp_nbgM; // work space of size nbgM - struct blasfeo_dvec *tmp_nsM; // work space of size nsM - struct blasfeo_dvec *Pb; // Pb - struct blasfeo_dvec *Zs_inv; - struct blasfeo_dmat *L; - struct blasfeo_dmat *Lh; - struct blasfeo_dmat *AL; - struct blasfeo_dmat *lq0; - struct blasfeo_dvec *tmp_m; - double *stat; // convergence statistics - int *use_hess_fact; - void *lq_work0; - double qp_res[4]; // infinity norm of residuals - int iter; // iteration number - int stat_max; // iterations saved in stat - int stat_m; // number of recorded stat per IPM iter - int use_Pb; - int status; // solver status - int lq_fact; // cache from arg - int mask_constr; // use constr mask - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_tree_ocp_qp_ipm_arg_memsize(struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_ipm_arg_create(struct d_tree_ocp_qp_dim *dim, struct d_tree_ocp_qp_ipm_arg *arg, void *mem); -// -void d_tree_ocp_qp_ipm_arg_set_default(enum hpipm_mode mode, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_iter_max(int *iter_max, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_alpha_min(double *alpha_min, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_mu0(double *mu0, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_tol_stat(double *tol_stat, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_tol_eq(double *tol_eq, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_tol_ineq(double *tol_ineq, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_tol_comp(double *tol_comp, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_reg_prim(double *reg, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_warm_start(int *warm_start, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_pred_corr(int *pred_corr, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_cond_pred_corr(int *value, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_comp_dual_sol_eq(int *value, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_comp_res_exit(int *value, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_lam_min(double *value, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_t_min(double *value, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_tau_min(double *value, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_split_step(int *value, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_t_lam_min(int *value, struct d_tree_ocp_qp_ipm_arg *arg); - -// -hpipm_size_t d_tree_ocp_qp_ipm_ws_memsize(struct d_tree_ocp_qp_dim *dim, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_ws_create(struct d_tree_ocp_qp_dim *dim, struct d_tree_ocp_qp_ipm_arg *arg, struct d_tree_ocp_qp_ipm_ws *ws, void *mem); -// -void d_tree_ocp_qp_ipm_get_status(struct d_tree_ocp_qp_ipm_ws *ws, int *status); -// -void d_tree_ocp_qp_ipm_get_iter(struct d_tree_ocp_qp_ipm_ws *ws, int *iter); -// -void d_tree_ocp_qp_ipm_get_max_res_stat(struct d_tree_ocp_qp_ipm_ws *ws, double *res_stat); -// -void d_tree_ocp_qp_ipm_get_max_res_eq(struct d_tree_ocp_qp_ipm_ws *ws, double *res_eq); -// -void d_tree_ocp_qp_ipm_get_max_res_ineq(struct d_tree_ocp_qp_ipm_ws *ws, double *res_ineq); -// -void d_tree_ocp_qp_ipm_get_max_res_comp(struct d_tree_ocp_qp_ipm_ws *ws, double *res_comp); -// -void d_tree_ocp_qp_ipm_get_stat(struct d_tree_ocp_qp_ipm_ws *ws, double **stat); -// -void d_tree_ocp_qp_ipm_get_stat_m(struct d_tree_ocp_qp_ipm_ws *ws, int *stat_m); -// -void d_tree_ocp_qp_init_var(struct d_tree_ocp_qp *qp, struct d_tree_ocp_qp_sol *qp_sol, struct d_tree_ocp_qp_ipm_arg *arg, struct d_tree_ocp_qp_ipm_ws *ws); -// -void d_tree_ocp_qp_ipm_abs_step(int kk, struct d_tree_ocp_qp *qp, struct d_tree_ocp_qp_sol *qp_sol, struct d_tree_ocp_qp_ipm_arg *arg, struct d_tree_ocp_qp_ipm_ws *ws); -// -void d_tree_ocp_qp_ipm_delta_step(int kk, struct d_tree_ocp_qp *qp, struct d_tree_ocp_qp_sol *qp_sol, struct d_tree_ocp_qp_ipm_arg *arg, struct d_tree_ocp_qp_ipm_ws *ws); -// -void d_tree_ocp_qp_ipm_solve(struct d_tree_ocp_qp *qp, struct d_tree_ocp_qp_sol *qp_sol, struct d_tree_ocp_qp_ipm_arg *arg, struct d_tree_ocp_qp_ipm_ws *ws); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_TREE_OCP_QP_IPM_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_kkt.h b/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_kkt.h deleted file mode 100644 index 4afd52fe4b..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_kkt.h +++ /dev/null @@ -1,52 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifdef __cplusplus -extern "C" { -#endif - - -// -void d_tree_ocp_qp_fact_solve_kkt_unconstr(struct d_tree_ocp_qp *qp, struct d_tree_ocp_qp_sol *qp_sol, struct d_tree_ocp_qp_ipm_arg *arg, struct d_tree_ocp_qp_ipm_ws *ws); -// -void d_tree_ocp_qp_fact_solve_kkt_step(struct d_tree_ocp_qp *qp, struct d_tree_ocp_qp_sol *qp_sol, struct d_tree_ocp_qp_ipm_arg *arg, struct d_tree_ocp_qp_ipm_ws *ws); -// -void d_tree_ocp_qp_fact_lq_solve_kkt_step(struct d_tree_ocp_qp *qp, struct d_tree_ocp_qp_sol *qp_sol, struct d_tree_ocp_qp_ipm_arg *arg, struct d_tree_ocp_qp_ipm_ws *ws); -// -void d_tree_ocp_qp_solve_kkt_step(struct d_tree_ocp_qp *qp, struct d_tree_ocp_qp_sol *qp_sol, struct d_tree_ocp_qp_ipm_arg *arg, struct d_tree_ocp_qp_ipm_ws *ws); - -#ifdef __cplusplus -} /* extern "C" */ -#endif diff --git a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_res.h b/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_res.h deleted file mode 100644 index fe499080ea..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_res.h +++ /dev/null @@ -1,106 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_TREE_OCP_QP_RES_H_ -#define HPIPM_D_TREE_OCP_QP_RES_H_ - - - -#include -#include - -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_tree_ocp_qp_res - { - struct d_tree_ocp_qp_dim *dim; - struct blasfeo_dvec *res_g; // q-residuals - struct blasfeo_dvec *res_b; // b-residuals - struct blasfeo_dvec *res_d; // d-residuals - struct blasfeo_dvec *res_m; // m-residuals - double res_max[4]; // max of residuals - double res_mu; // mu-residual - hpipm_size_t memsize; - }; - - - -struct d_tree_ocp_qp_res_ws - { - struct blasfeo_dvec *tmp_nbgM; // work space of size nbM+ngM - struct blasfeo_dvec *tmp_nsM; // work space of size nsM - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_tree_ocp_qp_res_memsize(struct d_tree_ocp_qp_dim *ocp_dim); -// -void d_tree_ocp_qp_res_create(struct d_tree_ocp_qp_dim *ocp_dim, struct d_tree_ocp_qp_res *res, void *mem); -// -hpipm_size_t d_tree_ocp_qp_res_ws_memsize(struct d_tree_ocp_qp_dim *ocp_dim); -// -void d_tree_ocp_qp_res_ws_create(struct d_tree_ocp_qp_dim *ocp_dim, struct d_tree_ocp_qp_res_ws *ws, void *mem); -// -void d_tree_ocp_qp_res_get_all(struct d_tree_ocp_qp_res *res, double **res_r, double **res_q, double **res_ls, double **res_us, double **res_b, double **res_d_lb, double **res_d_ub, double **res_d_lg, double **res_d_ug, double **res_d_ls, double **res_d_us, double **res_m_lb, double **res_m_ub, double **res_m_lg, double **res_m_ug, double **res_m_ls, double **res_m_us); -// -void d_tree_ocp_qp_res_compute(struct d_tree_ocp_qp *qp, struct d_tree_ocp_qp_sol *qp_sol, struct d_tree_ocp_qp_res *res, struct d_tree_ocp_qp_res_ws *ws); -// -void d_tree_ocp_qp_res_compute_lin(struct d_tree_ocp_qp *qp, struct d_tree_ocp_qp_sol *qp_sol, struct d_tree_ocp_qp_sol *qp_step, struct d_tree_ocp_qp_res *res, struct d_tree_ocp_qp_res_ws *ws); -// -void d_tree_ocp_qp_res_compute_inf_norm(struct d_tree_ocp_qp_res *res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_D_TREE_OCP_QP_RES_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_sol.h b/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_sol.h deleted file mode 100644 index 343d5e8ca6..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_sol.h +++ /dev/null @@ -1,100 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_TREE_OCP_QP_SOL_H_ -#define HPIPM_D_TREE_OCP_QP_SOL_H_ - - - -#include -#include - -#include "hpipm_d_tree_ocp_qp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - -struct d_tree_ocp_qp_sol - { - struct d_tree_ocp_qp_dim *dim; - struct blasfeo_dvec *ux; - struct blasfeo_dvec *pi; - struct blasfeo_dvec *lam; - struct blasfeo_dvec *t; - void *misc; - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t d_tree_ocp_qp_sol_memsize(struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_sol_create(struct d_tree_ocp_qp_dim *dim, struct d_tree_ocp_qp_sol *qp_sol, void *memory); -// -void d_tree_ocp_qp_sol_get_all(struct d_tree_ocp_qp *qp, struct d_tree_ocp_qp_sol *qp_sol, double **u, double **x, double **ls, double **us, double **pi, double **lam_lb, double **lam_ub, double **lam_lg, double **lam_ug, double **lam_ls, double **lam_us); -// -void d_tree_ocp_qp_sol_get(char *field, int node_edge, struct d_tree_ocp_qp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qp_sol_get_u(int node, struct d_tree_ocp_qp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qp_sol_get_x(int node, struct d_tree_ocp_qp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qp_sol_get_sl(int node, struct d_tree_ocp_qp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qp_sol_get_su(int node, struct d_tree_ocp_qp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qp_sol_get_pi(int edge, struct d_tree_ocp_qp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qp_sol_get_lam_lb(int node, struct d_tree_ocp_qp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qp_sol_get_lam_ub(int node, struct d_tree_ocp_qp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qp_sol_get_lam_lg(int node, struct d_tree_ocp_qp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qp_sol_get_lam_ug(int node, struct d_tree_ocp_qp_sol *qp_sol, double *vec); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_TREE_OCP_QP_SOL_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_utils.h b/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_utils.h deleted file mode 100644 index b689fdc0fa..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_utils.h +++ /dev/null @@ -1,83 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_TREE_OCP_QP_UTILS_H_ -#define HPIPM_D_TREE_OCP_QP_UTILS_H_ - - - -#include -#include - -#include "hpipm_d_tree_ocp_qp_dim.h" -#include "hpipm_d_tree_ocp_qp.h" -#include "hpipm_d_tree_ocp_qp_sol.h" -#include "hpipm_d_tree_ocp_qp_ipm.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void d_tree_ocp_qp_dim_print(struct d_tree_ocp_qp_dim *qp_dim); -// -//void d_tree_ocp_qp_dim_codegen(char *file_name, char *mode, struct d_tree_ocp_qp_dim *qp_dim); -// -void d_tree_ocp_qp_print(struct d_tree_ocp_qp_dim *qp_dim, struct d_tree_ocp_qp *qp); -// -//void d_tree_ocp_qp_codegen(char *file_name, char *mode, struct d_tree_ocp_qp_dim *qp_dim, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_sol_print(struct d_tree_ocp_qp_dim *qp_dim, struct d_tree_ocp_qp_sol *ocp_qp_sol); -// -void d_tree_ocp_qp_ipm_arg_print(struct d_tree_ocp_qp_dim *qp_dim, struct d_tree_ocp_qp_ipm_arg *arg); -// -//void d_tree_ocp_qp_ipm_arg_codegen(char *file_name, char *mode, struct d_tree_ocp_qp_dim *qp_dim, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_res_print(struct d_tree_ocp_qp_dim *qp_dim, struct d_tree_ocp_qp_res *ocp_qp_res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_TREE_OCP_QP_UTILS_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_m_dense_qp.h b/third_party/acados/include/hpipm/include/hpipm_m_dense_qp.h deleted file mode 100644 index 8bc101003e..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_m_dense_qp.h +++ /dev/null @@ -1,68 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - - -#ifndef HPIPM_M_DENSE_QP_H_ -#define HPIPM_M_DENSE_QP_H_ - - - -#include -#include - -#include "hpipm_d_dense_qp.h" -#include "hpipm_s_dense_qp.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -void cvt_d2s_dense_qp(struct d_dense_qp *qpd, struct s_dense_qp *qps); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_M_DENSE_QP_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_m_dense_qp_dim.h b/third_party/acados/include/hpipm/include/hpipm_m_dense_qp_dim.h deleted file mode 100644 index 4610321b97..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_m_dense_qp_dim.h +++ /dev/null @@ -1,68 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - - -#ifndef HPIPM_M_DENSE_QP_DIM_H_ -#define HPIPM_M_DENSE_QP_DIM_H_ - - - -#include -#include - -#include "hpipm_d_dense_qp_dim.h" -#include "hpipm_s_dense_qp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -void cvt_d2s_dense_qp_dim(struct d_dense_qp_dim *qpd, struct s_dense_qp_dim *qps); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_M_DENSE_QP_DIM_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_m_ocp_qp.h b/third_party/acados/include/hpipm/include/hpipm_m_ocp_qp.h deleted file mode 100644 index 95c3dad1aa..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_m_ocp_qp.h +++ /dev/null @@ -1,49 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#include -#include - -#ifdef __cplusplus -extern "C" { -#endif - -void m_cvt_d_ocp_qp_to_s_ocp_qp(struct d_ocp_qp *d_qp, struct s_ocp_qp *s_qp); - -#ifdef __cplusplus -} /* extern "C" */ -#endif diff --git a/third_party/acados/include/hpipm/include/hpipm_m_ocp_qp_ipm_hard.h b/third_party/acados/include/hpipm/include/hpipm_m_ocp_qp_ipm_hard.h deleted file mode 100644 index 1c44acee2e..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_m_ocp_qp_ipm_hard.h +++ /dev/null @@ -1,115 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#include -#include - -#ifdef __cplusplus -extern "C" { -#endif - - -struct m_ipm_hard_ocp_qp_workspace - { - struct d_ipm_hard_core_qp_workspace *core_workspace; - struct blasfeo_dvec *dux; - struct blasfeo_dvec *dpi; - struct blasfeo_dvec *dt_lb; - struct blasfeo_dvec *dt_lg; - struct blasfeo_svec *sdux; // XXX - struct blasfeo_svec *sdpi; // XXX - struct blasfeo_dvec *res_g; // q-residuals - struct blasfeo_dvec *res_b; // b-residuals - struct blasfeo_dvec *res_d; // d-residuals XXX remove ??? - struct blasfeo_dvec *res_d_lb; // d-residuals - struct blasfeo_dvec *res_d_ub; // d-residuals - struct blasfeo_dvec *res_d_lg; // d-residuals - struct blasfeo_dvec *res_d_ug; // d-residuals - struct blasfeo_dvec *res_m; // m-residuals - struct blasfeo_dvec *res_m_lb; // m-residuals - struct blasfeo_dvec *res_m_ub; // m-residuals - struct blasfeo_dvec *res_m_lg; // m-residuals - struct blasfeo_dvec *res_m_ug; // m-residuals - struct blasfeo_svec *sres_g; // q-residuals // XXX - struct blasfeo_svec *sres_b; // b-residuals // XXX - struct blasfeo_dvec *Qx_lb; // hessian update - struct blasfeo_dvec *Qx_lg; // hessian update - struct blasfeo_dvec *qx_lb; // gradient update - struct blasfeo_dvec *qx_lg; // gradient update - struct blasfeo_svec *sQx_lb; // hessian update // XXX - struct blasfeo_svec *sQx_lg; // hessian update // XXX - struct blasfeo_svec *sqx_lb; // gradient update // XXX - struct blasfeo_svec *sqx_lg; // gradient update // XXX - struct blasfeo_dvec *tmp_nbM; // work space of size nbM - struct blasfeo_svec *tmp_nxM; // work space of size nxM // XXX - struct blasfeo_dvec *tmp_ngM; // work space of size ngM - struct blasfeo_svec *Pb; // Pb // XXX - struct blasfeo_smat *L; // XXX - struct blasfeo_smat *AL; // XXX - struct blasfeo_svec *sSx; // scaling - struct blasfeo_svec *sSi; // scaling inverted - double *stat; // convergence statistics - double res_mu; // mu-residual - int iter; // iteration number - int compute_Pb; - int scale; - }; - - - -struct m_ipm_hard_ocp_qp_arg - { - double alpha_min; // exit cond on step length - double mu_max; // exit cond on duality measure - double mu0; // initial value for duality measure - int iter_max; // exit cond in iter number - }; - - - -// -hpipm_size_t m_memsize_ipm_hard_ocp_qp(struct d_ocp_qp *d_qp, struct s_ocp_qp *s_qp, struct m_ipm_hard_ocp_qp_arg *arg); -// -void m_create_ipm_hard_ocp_qp(struct d_ocp_qp *d_qp, struct s_ocp_qp *s_qp, struct m_ipm_hard_ocp_qp_arg *arg, struct m_ipm_hard_ocp_qp_workspace *ws, void *mem); -// -void m_solve_ipm_hard_ocp_qp(struct d_ocp_qp *d_qp, struct s_ocp_qp *s_qp, struct d_ocp_qp_sol *qp_sol, struct m_ipm_hard_ocp_qp_workspace *ws); -// -void m_solve_ipm2_hard_ocp_qp(struct d_ocp_qp *d_qp, struct s_ocp_qp *s_qp, struct d_ocp_qp_sol *qp_sol, struct m_ipm_hard_ocp_qp_workspace *ws); - -#ifdef __cplusplus -} /* extern "C" */ -#endif diff --git a/third_party/acados/include/hpipm/include/hpipm_m_ocp_qp_kkt.h b/third_party/acados/include/hpipm/include/hpipm_m_ocp_qp_kkt.h deleted file mode 100644 index 032fe95b1f..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_m_ocp_qp_kkt.h +++ /dev/null @@ -1,45 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifdef __cplusplus -extern "C" { -#endif - -void m_fact_solve_kkt_step_hard_ocp_qp(struct d_ocp_qp *d_qp, struct s_ocp_qp *s_qp, struct m_ipm_hard_ocp_qp_workspace *ws); -void m_solve_kkt_step_hard_ocp_qp(struct d_ocp_qp *d_qp, struct s_ocp_qp *s_qp, struct m_ipm_hard_ocp_qp_workspace *ws); - -#ifdef __cplusplus -} /* extern "C" */ -#endif diff --git a/third_party/acados/include/hpipm/include/hpipm_s_cast_qcqp.h b/third_party/acados/include/hpipm/include/hpipm_s_cast_qcqp.h deleted file mode 100644 index ba01ecb3bd..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_cast_qcqp.h +++ /dev/null @@ -1,72 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_S_CAST_QCQP_H_ -#define HPIPM_S_CAST_QCQP_H_ - - - -#include -#include - -#include "hpipm_s_dense_qcqp.h" -#include "hpipm_s_dense_qcqp_sol.h" -#include "hpipm_s_ocp_qcqp.h" -#include "hpipm_s_ocp_qcqp_dim.h" -#include "hpipm_s_ocp_qcqp_sol.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void s_cast_qcqp_compute_dim(struct s_ocp_qcqp_dim *ocp_dim, struct s_dense_qcqp_dim *dense_dim); -// -void s_cast_qcqp_cond(struct s_ocp_qcqp *ocp_qp, struct s_dense_qcqp *dense_qp); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_CAST_QCQP_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_cond.h b/third_party/acados/include/hpipm/include/hpipm_s_cond.h deleted file mode 100644 index 30116798b7..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_cond.h +++ /dev/null @@ -1,137 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_S_COND_H_ -#define HPIPM_S_COND_H_ - - - -#include -#include - -#include "hpipm_s_dense_qp.h" -#include "hpipm_s_dense_qp_sol.h" -#include "hpipm_s_ocp_qp.h" -#include "hpipm_s_ocp_qp_dim.h" -#include "hpipm_s_ocp_qp_sol.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_cond_qp_arg - { - int cond_last_stage; // condense last stage - int cond_alg; // condensing algorithm: 0 N2-nx3, 1 N3-nx2 - int comp_prim_sol; // primal solution (v) - int comp_dual_sol_eq; // dual solution equality constr (pi) - int comp_dual_sol_ineq; // dual solution inequality constr (lam t) - int square_root_alg; // square root algorithm (faster but requires RSQ>0) - hpipm_size_t memsize; - }; - - - -struct s_cond_qp_ws - { - struct blasfeo_smat *Gamma; - struct blasfeo_smat *GammaQ; - struct blasfeo_smat *L; - struct blasfeo_smat *Lx; - struct blasfeo_smat *AL; - struct blasfeo_svec *Gammab; - struct blasfeo_svec *l; - struct blasfeo_svec *tmp_nbgM; - struct blasfeo_svec *tmp_nuxM; - int bs; // block size - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_cond_qp_arg_memsize(); -// -void s_cond_qp_arg_create(struct s_cond_qp_arg *cond_arg, void *mem); -// -void s_cond_qp_arg_set_default(struct s_cond_qp_arg *cond_arg); -// condensing algorithm: 0 N2-nx3, 1 N3-nx2 -void s_cond_qp_arg_set_cond_alg(int cond_alg, struct s_cond_qp_arg *cond_arg); -// set riccati-like algorithm: 0 classical, 1 square-root -void s_cond_qp_arg_set_ric_alg(int ric_alg, struct s_cond_qp_arg *cond_arg); -// condense last stage: 0 last stage disregarded, 1 last stage condensed too -void s_cond_qp_arg_set_cond_last_stage(int cond_last_stage, struct s_cond_qp_arg *cond_arg); -// -void s_cond_qp_arg_set_comp_prim_sol(int value, struct s_cond_qp_arg *cond_arg); -// -void s_cond_qp_arg_set_comp_dual_sol_eq(int value, struct s_cond_qp_arg *cond_arg); -// -void s_cond_qp_arg_set_comp_dual_sol_ineq(int value, struct s_cond_qp_arg *cond_arg); - -// -void s_cond_qp_compute_dim(struct s_ocp_qp_dim *ocp_dim, struct s_dense_qp_dim *dense_dim); -// -hpipm_size_t s_cond_qp_ws_memsize(struct s_ocp_qp_dim *ocp_dim, struct s_cond_qp_arg *cond_arg); -// -void s_cond_qp_ws_create(struct s_ocp_qp_dim *ocp_dim, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws, void *mem); -// -void s_cond_qp_cond(struct s_ocp_qp *ocp_qp, struct s_dense_qp *dense_qp, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_cond_qp_cond_lhs(struct s_ocp_qp *ocp_qp, struct s_dense_qp *dense_qp, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_cond_qp_cond_rhs(struct s_ocp_qp *ocp_qp, struct s_dense_qp *dense_qp, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_cond_qp_expand_sol(struct s_ocp_qp *ocp_qp, struct s_dense_qp_sol *dense_qp_sol, struct s_ocp_qp_sol *ocp_qp_sol, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// TODO remove -void s_cond_qp_expand_primal_sol(struct s_ocp_qp *ocp_qp, struct s_dense_qp_sol *dense_qp_sol, struct s_ocp_qp_sol *ocp_qp_sol, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); - -// -void s_cond_qp_update(int *idxc, struct s_ocp_qp *ocp_qp, struct s_dense_qp *dense_qp, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_COND_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_cond_aux.h b/third_party/acados/include/hpipm/include/hpipm_s_cond_aux.h deleted file mode 100644 index 003472ab9f..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_cond_aux.h +++ /dev/null @@ -1,92 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_S_COND_AUX_H_ -#define HPIPM_S_COND_AUX_H_ - - - -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void s_cond_BAbt(struct s_ocp_qp *ocp_qp, struct blasfeo_smat *BAbt2, struct blasfeo_svec *b2, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_cond_BAt(struct s_ocp_qp *ocp_qp, struct blasfeo_smat *BAbt2, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_cond_b(struct s_ocp_qp *ocp_qp, struct blasfeo_svec *b2, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_cond_RSQrq(struct s_ocp_qp *ocp_qp, struct blasfeo_smat *RSQrq2, struct blasfeo_svec *rq2, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_cond_RSQ(struct s_ocp_qp *ocp_qp, struct blasfeo_smat *RSQrq2, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_cond_rq(struct s_ocp_qp *ocp_qp, struct blasfeo_svec *rq2, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_cond_DCtd(struct s_ocp_qp *ocp_qp, int *idxb2, struct blasfeo_smat *DCt2, struct blasfeo_svec *d2, struct blasfeo_svec *d_mask2, int *idxs_rev2, struct blasfeo_svec *Z2, struct blasfeo_svec *z2, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_cond_DCt(struct s_ocp_qp *ocp_qp, int *idxb2, struct blasfeo_smat *DCt2, int *idxs_rev2, struct blasfeo_svec *Z2, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_cond_d(struct s_ocp_qp *ocp_qp, struct blasfeo_svec *d2, struct blasfeo_svec *d_mask2, struct blasfeo_svec *z2, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_expand_sol(struct s_ocp_qp *ocp_qp, struct s_dense_qp_sol *dense_qp_sol, struct s_ocp_qp_sol *ocp_qp_sol, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_expand_primal_sol(struct s_ocp_qp *ocp_qp, struct s_dense_qp_sol *dense_qp_sol, struct s_ocp_qp_sol *ocp_qp_sol, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); - -// -void s_update_cond_BAbt(int *idxc, struct s_ocp_qp *ocp_qp, struct blasfeo_smat *BAbt2, struct blasfeo_svec *b2, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_update_cond_RSQrq_N2nx3(int *idxc, struct s_ocp_qp *ocp_qp, struct blasfeo_smat *RSQrq2, struct blasfeo_svec *rq2, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_update_cond_DCtd(int *idxc, struct s_ocp_qp *ocp_qp, int *idxb2, struct blasfeo_smat *DCt2, struct blasfeo_svec *d2, int *idxs2, struct blasfeo_svec *Z2, struct blasfeo_svec *z2, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_COND_AUX_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_cond_qcqp.h b/third_party/acados/include/hpipm/include/hpipm_s_cond_qcqp.h deleted file mode 100644 index c36678abd5..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_cond_qcqp.h +++ /dev/null @@ -1,130 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_S_COND_QCQP_H_ -#define HPIPM_S_COND_QCQP_H_ - - - -#include -#include - -#include "hpipm_s_dense_qcqp.h" -#include "hpipm_s_dense_qcqp_sol.h" -#include "hpipm_s_ocp_qcqp.h" -#include "hpipm_s_ocp_qcqp_dim.h" -#include "hpipm_s_ocp_qcqp_sol.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_cond_qcqp_arg - { - struct s_cond_qp_arg *qp_arg; - int cond_last_stage; // condense last stage -// int cond_variant; // TODO - int comp_prim_sol; // primal solution (v) - int comp_dual_sol_eq; // dual solution equality constr (pi) - int comp_dual_sol_ineq; // dual solution equality constr (lam t) - int square_root_alg; // square root algorithm (faster but requires RSQ>0) - hpipm_size_t memsize; - }; - - - -struct s_cond_qcqp_ws - { - struct s_cond_qp_ws *qp_ws; - struct blasfeo_smat *hess_array; // TODO remove - struct blasfeo_smat *zero_hess; // TODO remove - struct blasfeo_svec *zero_grad; // TODO remove - struct blasfeo_svec *grad_array; // TODO remove - struct blasfeo_svec *tmp_nvc; - struct blasfeo_svec *tmp_nuxM; - struct blasfeo_smat *GammaQ; - struct blasfeo_smat *tmp_DCt; - struct blasfeo_smat *tmp_nuM_nxM; -// struct blasfeo_svec *d_qp; -// struct blasfeo_svec *d_mask_qp; - hpipm_size_t memsize; - }; - - -// -hpipm_size_t s_cond_qcqp_arg_memsize(); -// -void s_cond_qcqp_arg_create(struct s_cond_qcqp_arg *cond_arg, void *mem); -// -void s_cond_qcqp_arg_set_default(struct s_cond_qcqp_arg *cond_arg); -// set riccati-like algorithm: 0 classical, 1 square-root -void s_cond_qcqp_arg_set_ric_alg(int ric_alg, struct s_cond_qcqp_arg *cond_arg); -// condense last stage: 0 last stage disregarded, 1 last stage condensed too -void s_cond_qcqp_arg_set_cond_last_stage(int cond_last_stage, struct s_cond_qcqp_arg *cond_arg); - -// -void s_cond_qcqp_compute_dim(struct s_ocp_qcqp_dim *ocp_dim, struct s_dense_qcqp_dim *dense_dim); -// -hpipm_size_t s_cond_qcqp_ws_memsize(struct s_ocp_qcqp_dim *ocp_dim, struct s_cond_qcqp_arg *cond_arg); -// -void s_cond_qcqp_ws_create(struct s_ocp_qcqp_dim *ocp_dim, struct s_cond_qcqp_arg *cond_arg, struct s_cond_qcqp_ws *cond_ws, void *mem); -// -void s_cond_qcqp_qc(struct s_ocp_qcqp *ocp_qp, struct blasfeo_smat *Hq2, int *Hq_nzero2, struct blasfeo_smat *Ct2, struct blasfeo_svec *d2, struct s_cond_qcqp_arg *cond_arg, struct s_cond_qcqp_ws *cond_ws); -// -void s_cond_qcqp_qc_lhs(struct s_ocp_qcqp *ocp_qp, struct blasfeo_smat *Hq2, int *Hq_nzero2, struct blasfeo_smat *Ct2, struct s_cond_qcqp_arg *cond_arg, struct s_cond_qcqp_ws *cond_ws); -// -void s_cond_qcqp_qc_rhs(struct s_ocp_qcqp *ocp_qp, struct blasfeo_svec *d2, struct s_cond_qcqp_arg *cond_arg, struct s_cond_qcqp_ws *cond_ws); -// -void s_cond_qcqp_cond(struct s_ocp_qcqp *ocp_qp, struct s_dense_qcqp *dense_qp, struct s_cond_qcqp_arg *cond_arg, struct s_cond_qcqp_ws *cond_ws); -// -void s_cond_qcqp_cond_rhs(struct s_ocp_qcqp *ocp_qp, struct s_dense_qcqp *dense_qp, struct s_cond_qcqp_arg *cond_arg, struct s_cond_qcqp_ws *cond_ws); -// -void s_cond_qcqp_cond_lhs(struct s_ocp_qcqp *ocp_qp, struct s_dense_qcqp *dense_qp, struct s_cond_qcqp_arg *cond_arg, struct s_cond_qcqp_ws *cond_ws); -// -void s_cond_qcqp_expand_sol(struct s_ocp_qcqp *ocp_qp, struct s_dense_qcqp_sol *dense_qp_sol, struct s_ocp_qcqp_sol *ocp_qp_sol, struct s_cond_qcqp_arg *cond_arg, struct s_cond_qcqp_ws *cond_ws); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_COND_QCQP_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_core_qp_ipm.h b/third_party/acados/include/hpipm/include/hpipm_s_core_qp_ipm.h deleted file mode 100644 index 480392c7d9..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_core_qp_ipm.h +++ /dev/null @@ -1,101 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_CORE_QP_IPM_ -#define HPIPM_S_CORE_QP_IPM_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - -struct s_core_qp_ipm_workspace - { - float *v; // primal variables - float *pi; // equality constraints multipliers - float *lam; // inequality constraints multipliers - float *t; // inequality constraints slacks - float *t_inv; // inverse of t - float *v_bkp; // backup of primal variables - float *pi_bkp; // backup of equality constraints multipliers - float *lam_bkp; // backup of inequality constraints multipliers - float *t_bkp; // backup of inequality constraints slacks - float *dv; // step in v - float *dpi; // step in pi - float *dlam; // step in lam - float *dt; // step in t - float *res_g; // q-residuals - float *res_b; // b-residuals - float *res_d; // d-residuals - float *res_m; // m-residuals - float *res_m_bkp; // m-residuals - float *Gamma; // Hessian update - float *gamma; // gradient update - float alpha_prim; // step length - float alpha_dual; // step length - float alpha; // step length - float sigma; // centering XXX - float mu; // duality measuere - float mu_aff; // affine duality measuere - float nc_inv; // 1.0/nc, where nc is the total number of constraints - float nc_mask_inv; // 1.0/nc_mask - float lam_min; // min value in lam vector - float t_min; // min value in t vector - float t_min_inv; // inverse of min value in t vector - float tau_min; // min value of barrier parameter - int nv; // number of primal variables - int ne; // number of equality constraints - int nc; // (twice the) number of (two-sided) inequality constraints - int nc_mask; // total number of ineq constr after masking - int split_step; // use different step for primal and dual variables - int t_lam_min; // clip t and lam also in solution, or only in Gamma computation - hpipm_size_t memsize; // memory size (in bytes) of workspace - }; - - - -// -hpipm_size_t s_memsize_core_qp_ipm(int nv, int ne, int nc); -// -void s_create_core_qp_ipm(int nv, int ne, int nc, struct s_core_qp_ipm_workspace *workspace, void *mem); -// -void s_core_qp_ipm(struct s_core_qp_ipm_workspace *workspace); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // HPIPM_S_CORE_QP_IPM_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_core_qp_ipm_aux.h b/third_party/acados/include/hpipm/include/hpipm_s_core_qp_ipm_aux.h deleted file mode 100644 index 1ac3d7ede9..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_core_qp_ipm_aux.h +++ /dev/null @@ -1,68 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_CORE_QP_IPM_AUX_ -#define HPIPM_S_CORE_QP_IPM_AUX_ - -#ifdef __cplusplus -extern "C" { -#endif - -// -void s_compute_Gamma_gamma_qp(float *res_d, float *res_m, struct s_core_qp_ipm_workspace *rws); -// -void s_compute_gamma_qp(float *res_d, float *res_m, struct s_core_qp_ipm_workspace *rws); -// -void s_compute_lam_t_qp(float *res_d, float *res_m, float *dlam, float *dt, struct s_core_qp_ipm_workspace *rws); -// -void s_compute_alpha_qp(struct s_core_qp_ipm_workspace *rws); -// -void s_update_var_qp(struct s_core_qp_ipm_workspace *rws); -// -void s_compute_mu_aff_qp(struct s_core_qp_ipm_workspace *rws); -// -void s_backup_res_m(struct s_core_qp_ipm_workspace *rws); -// -void s_compute_centering_correction_qp(struct s_core_qp_ipm_workspace *rws); -// -void s_compute_centering_qp(struct s_core_qp_ipm_workspace *rws); -// -void s_compute_tau_min_qp(struct s_core_qp_ipm_workspace *rws); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // HPIPM_S_CORE_QP_IPM_AUX_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp.h b/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp.h deleted file mode 100644 index d03c065375..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp.h +++ /dev/null @@ -1,200 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_S_DENSE_QCQP_H_ -#define HPIPM_S_DENSE_QCQP_H_ - - - -#include -#include - -#include "hpipm_s_dense_qcqp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_dense_qcqp - { - struct s_dense_qcqp_dim *dim; - struct blasfeo_smat *Hv; // hessian of cost & vector work space - struct blasfeo_smat *A; // equality constraint matrix - struct blasfeo_smat *Ct; // inequality constraints matrix - struct blasfeo_smat *Hq; // hessians of quadratic constraints - struct blasfeo_svec *gz; // gradient of cost & gradient of slacks - struct blasfeo_svec *b; // equality constraint vector - struct blasfeo_svec *d; // inequality constraints vector - struct blasfeo_svec *d_mask; // inequality constraints mask vector - struct blasfeo_svec *m; // rhs of complementarity condition - struct blasfeo_svec *Z; // (diagonal) hessian of slacks - int *idxb; // indices of box constrained variables within [u; x] - int *idxs_rev; // index of soft constraints (reverse storage) - int *Hq_nzero; // for each int, the last 3 bits ...abc, {a,b,c}=0 => {R,S,Q}=0 - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t s_dense_qcqp_memsize(struct s_dense_qcqp_dim *dim); -// -void s_dense_qcqp_create(struct s_dense_qcqp_dim *dim, struct s_dense_qcqp *qp, void *memory); - -// -void s_dense_qcqp_set(char *field, void *value, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_H(float *H, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_g(float *g, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_A(float *A, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_b(float *b, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_idxb(int *idxb, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_lb(float *lb, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_lb_mask(float *lb, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_ub(float *ub, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_ub_mask(float *ub, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_C(float *C, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_lg(float *lg, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_lg_mask(float *lg, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_ug(float *ug, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_ug_mask(float *ug, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_Hq(float *Hq, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_gq(float *gq, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_uq(float *uq, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_uq_mask(float *uq, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_idxs(int *idxs, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_idxs_rev(int *idxs_rev, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_Zl(float *Zl, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_Zu(float *Zu, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_zl(float *zl, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_zu(float *zu, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_ls(float *ls, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_ls_mask(float *ls, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_us(float *us, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_us_mask(float *us, struct s_dense_qcqp *qp); - -// getters (COLMAJ) - -void s_dense_qcqp_get_H(struct s_dense_qcqp *qp, float *H); -// -void s_dense_qcqp_get_g(struct s_dense_qcqp *qp, float *g); -// -void s_dense_qcqp_get_A(struct s_dense_qcqp *qp, float *A); -// -void s_dense_qcqp_get_b(struct s_dense_qcqp *qp, float *b); -// -void s_dense_qcqp_get_idxb(struct s_dense_qcqp *qp, int *idxb); -// -void s_dense_qcqp_get_lb(struct s_dense_qcqp *qp, float *lb); -// -void s_dense_qcqp_get_lb_mask(struct s_dense_qcqp *qp, float *lb); -// -void s_dense_qcqp_get_ub(struct s_dense_qcqp *qp, float *ub); -// -void s_dense_qcqp_get_ub_mask(struct s_dense_qcqp *qp, float *ub); -// -void s_dense_qcqp_get_C(struct s_dense_qcqp *qp, float *C); -// -void s_dense_qcqp_get_lg(struct s_dense_qcqp *qp, float *lg); -// -void s_dense_qcqp_get_lg_mask(struct s_dense_qcqp *qp, float *lg); -// -void s_dense_qcqp_get_ug(struct s_dense_qcqp *qp, float *ug); -// -void s_dense_qcqp_get_ug_mask(struct s_dense_qcqp *qp, float *ug); -// -void s_dense_qcqp_get_idxs(struct s_dense_qcqp *qp, int *idxs); -// -void s_dense_qcqp_get_idxs_rev(struct s_dense_qcqp *qp, int *idxs_rev); -// -void s_dense_qcqp_get_Zl(struct s_dense_qcqp *qp, float *Zl); -// -void s_dense_qcqp_get_Zu(struct s_dense_qcqp *qp, float *Zu); -// -void s_dense_qcqp_get_zl(struct s_dense_qcqp *qp, float *zl); -// -void s_dense_qcqp_get_zu(struct s_dense_qcqp *qp, float *zu); -// -void s_dense_qcqp_get_ls(struct s_dense_qcqp *qp, float *ls); -// -void s_dense_qcqp_get_ls_mask(struct s_dense_qcqp *qp, float *ls); -// -void s_dense_qcqp_get_us(struct s_dense_qcqp *qp, float *us); -// -void s_dense_qcqp_get_us_mask(struct s_dense_qcqp *qp, float *us); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_DENSE_QCQP_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_dim.h b/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_dim.h deleted file mode 100644 index 04908c2c3a..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_dim.h +++ /dev/null @@ -1,99 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_DENSE_QCQP_DIM_H_ -#define HPIPM_S_DENSE_QCQP_DIM_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_dense_qcqp_dim - { - struct s_dense_qp_dim *qp_dim; // dim of qp approximation - int nv; // number of variables - int ne; // number of equality constraints - int nb; // number of box constraints - int ng; // number of general constraints - int nq; // number of quadratic constraints - int nsb; // number of softened box constraints - int nsg; // number of softened general constraints - int nsq; // number of softened quadratic constraints - int ns; // number of softened constraints (nsb+nsg+nsq) TODO number of slacks - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_dense_qcqp_dim_memsize(); -// -void s_dense_qcqp_dim_create(struct s_dense_qcqp_dim *dim, void *memory); -// -void s_dense_qcqp_dim_set(char *fiels_name, int value, struct s_dense_qcqp_dim *dim); -// -void s_dense_qcqp_dim_set_nv(int value, struct s_dense_qcqp_dim *dim); -// -void s_dense_qcqp_dim_set_ne(int value, struct s_dense_qcqp_dim *dim); -// -void s_dense_qcqp_dim_set_nb(int value, struct s_dense_qcqp_dim *dim); -// -void s_dense_qcqp_dim_set_ng(int value, struct s_dense_qcqp_dim *dim); -// -void s_dense_qcqp_dim_set_nq(int value, struct s_dense_qcqp_dim *dim); -// -void s_dense_qcqp_dim_set_nsb(int value, struct s_dense_qcqp_dim *dim); -// -void s_dense_qcqp_dim_set_nsg(int value, struct s_dense_qcqp_dim *dim); -// -void s_dense_qcqp_dim_set_nsq(int value, struct s_dense_qcqp_dim *dim); -// -void s_dense_qcqp_dim_set_ns(int value, struct s_dense_qcqp_dim *dim); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_S_DENSE_QCQP_DIM_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_ipm.h b/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_ipm.h deleted file mode 100644 index 8f85768ee3..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_ipm.h +++ /dev/null @@ -1,204 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_S_DENSE_QCQP_IPM_H_ -#define HPIPM_S_DENSE_QCQP_IPM_H_ - - - -#include -#include - -#include -#include -#include -#include -#include - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_dense_qcqp_ipm_arg - { - struct s_dense_qp_ipm_arg *qp_arg; - float mu0; // initial value for duality measure - float alpha_min; // exit cond on step length - float res_g_max; // exit cond on inf norm of residuals - float res_b_max; // exit cond on inf norm of residuals - float res_d_max; // exit cond on inf norm of residuals - float res_m_max; // exit cond on inf norm of residuals - float reg_prim; // reg of primal hessian - float reg_dual; // reg of dual hessian - float lam_min; // min value in lam vector - float t_min; // min value in t vector - int iter_max; // exit cond in iter number - int stat_max; // iterations saved in stat - int pred_corr; // Mehrotra's predictor-corrector IPM algirthm - int cond_pred_corr; // conditional Mehrotra's predictor-corrector - int scale; // scale hessian - int itref_pred_max; // max number of iterative refinement steps for predictor step - int itref_corr_max; // max number of iterative refinement steps for corrector step - int warm_start; // 0 no warm start, 1 warm start primal sol, 2 warm start primal and dual sol - int lq_fact; // 0 syrk+potrf, 1 mix, 2 lq - int abs_form; // absolute IPM formulation - int comp_res_exit; // compute residuals on exit (only for abs_form==1) - int comp_res_pred; // compute residuals of prediction - int split_step; // use different step for primal and dual variables - int t_lam_min; // clip t and lam: 0 no, 1 in Gamma computation, 2 in solution - int mode; - hpipm_size_t memsize; - }; - - - -struct s_dense_qcqp_ipm_ws - { -// float qp_res[4]; // infinity norm of residuals - struct s_dense_qp_ipm_ws *qp_ws; - struct s_dense_qp *qp; - struct s_dense_qp_sol *qp_sol; - struct s_dense_qcqp_res_ws *qcqp_res_ws; - struct s_dense_qcqp_res *qcqp_res; - struct blasfeo_svec *tmp_nv; -// float *stat; // convergence statistics -// void *lq_work0; -// void *lq_work1; - int iter; // iteration number -// int stat_max; // iterations saved in stat -// int stat_m; // numer of recorded stat per ipm iter -// int scale; -// int use_hess_fact; - int status; - hpipm_size_t memsize; // memory size (in bytes) of workspace - }; - - - -// -hpipm_size_t s_dense_qcqp_ipm_arg_memsize(struct s_dense_qcqp_dim *dim); -// -void s_dense_qcqp_ipm_arg_create(struct s_dense_qcqp_dim *dim, struct s_dense_qcqp_ipm_arg *arg, void *mem); -// -void s_dense_qcqp_ipm_arg_set_default(enum hpipm_mode mode, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set(char *field, void *value, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_iter_max(int *iter_max, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_alpha_min(float *alpha_min, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_mu0(float *mu0, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_tol_stat(float *tol_stat, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_tol_eq(float *tol_eq, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_tol_ineq(float *tol_ineq, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_tol_comp(float *tol_comp, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_reg_prim(float *reg, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_reg_dual(float *reg, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_warm_start(int *warm_start, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_pred_corr(int *pred_corr, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_cond_pred_corr(int *cond_pred_corr, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_comp_res_pred(int *comp_res_pred, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_comp_res_exit(int *comp_res_exit, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_lam_min(float *value, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_t_min(float *value, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_split_step(int *value, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_t_lam_min(int *value, struct s_dense_qcqp_ipm_arg *arg); - -// -hpipm_size_t s_dense_qcqp_ipm_ws_memsize(struct s_dense_qcqp_dim *qp_dim, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_ws_create(struct s_dense_qcqp_dim *qp_dim, struct s_dense_qcqp_ipm_arg *arg, struct s_dense_qcqp_ipm_ws *ws, void *mem); -// -void s_dense_qcqp_ipm_get(char *field, struct s_dense_qcqp_ipm_ws *ws, void *value); -// -void s_dense_qcqp_ipm_get_status(struct s_dense_qcqp_ipm_ws *ws, int *status); -// -void s_dense_qcqp_ipm_get_iter(struct s_dense_qcqp_ipm_ws *ws, int *iter); -// -void s_dense_qcqp_ipm_get_max_res_stat(struct s_dense_qcqp_ipm_ws *ws, float *res_stat); -// -void s_dense_qcqp_ipm_get_max_res_eq(struct s_dense_qcqp_ipm_ws *ws, float *res_eq); -// -void s_dense_qcqp_ipm_get_max_res_ineq(struct s_dense_qcqp_ipm_ws *ws, float *res_ineq); -// -void s_dense_qcqp_ipm_get_max_res_comp(struct s_dense_qcqp_ipm_ws *ws, float *res_comp); -// -void s_dense_qcqp_ipm_get_stat(struct s_dense_qcqp_ipm_ws *ws, float **stat); -// -void s_dense_qcqp_ipm_get_stat_m(struct s_dense_qcqp_ipm_ws *ws, int *stat_m); -#if 0 -// -void s_dense_qcqp_init_var(struct s_dense_qcqp *qp, struct s_dense_qcqp_sol *qp_sol, struct s_dense_qcqp_ipm_arg *arg, struct s_dense_qcqp_ipm_ws *ws); -#endif -// -void s_dense_qcqp_ipm_solve(struct s_dense_qcqp *qp, struct s_dense_qcqp_sol *qp_sol, struct s_dense_qcqp_ipm_arg *arg, struct s_dense_qcqp_ipm_ws *ws); -#if 0 -// -void s_dense_qcqp_ipm_predict(struct s_dense_qcqp *qp, struct s_dense_qcqp_sol *qp_sol, struct s_dense_qcqp_ipm_arg *arg, struct s_dense_qcqp_ipm_ws *ws); -// -void s_dense_qcqp_ipm_sens(struct s_dense_qcqp *qp, struct s_dense_qcqp_sol *qp_sol, struct s_dense_qcqp_ipm_arg *arg, struct s_dense_qcqp_ipm_ws *ws); -#endif - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_DENSE_QCQP_IPM_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_res.h b/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_res.h deleted file mode 100644 index 779658cc8f..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_res.h +++ /dev/null @@ -1,108 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_DENSE_QCQP_RES_H_ -#define HPIPM_S_DENSE_QCQP_RES_H_ - - - -#include -#include - -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_dense_qcqp_res - { - struct s_dense_qcqp_dim *dim; - struct blasfeo_svec *res_g; // q-residuals - struct blasfeo_svec *res_b; // b-residuals - struct blasfeo_svec *res_d; // d-residuals - struct blasfeo_svec *res_m; // m-residuals - float res_max[4]; // infinity norm of residuals - float res_mu; // mu-residual - hpipm_size_t memsize; - }; - - - -struct s_dense_qcqp_res_ws - { - struct blasfeo_svec *tmp_nv; // work space of size nv - struct blasfeo_svec *tmp_nbgq; // work space of size nbM+ngM+nqM - struct blasfeo_svec *tmp_ns; // work space of size nsM - struct blasfeo_svec *q_fun; // value for evaluation of quadr constr - struct blasfeo_svec *q_adj; // value for adjoint of quadr constr - int use_q_fun; // reuse cached value for evaluation of quadr constr - int use_q_adj; // reuse cached value for adjoint of quadr constr - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_dense_qcqp_res_memsize(struct s_dense_qcqp_dim *dim); -// -void s_dense_qcqp_res_create(struct s_dense_qcqp_dim *dim, struct s_dense_qcqp_res *res, void *mem); -// -hpipm_size_t s_dense_qcqp_res_ws_memsize(struct s_dense_qcqp_dim *dim); -// -void s_dense_qcqp_res_ws_create(struct s_dense_qcqp_dim *dim, struct s_dense_qcqp_res_ws *workspace, void *mem); -// -void s_dense_qcqp_res_compute(struct s_dense_qcqp *qp, struct s_dense_qcqp_sol *qp_sol, struct s_dense_qcqp_res *res, struct s_dense_qcqp_res_ws *ws); -// -void s_dense_qcqp_res_compute_inf_norm(struct s_dense_qcqp_res *res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_S_DENSE_QCQP_RES_H_ - - - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_sol.h b/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_sol.h deleted file mode 100644 index 197a690e52..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_sol.h +++ /dev/null @@ -1,86 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_S_DENSE_QCQP_SOL_H_ -#define HPIPM_S_DENSE_QCQP_SOL_H_ - - - -#include -#include - -#include "hpipm_s_dense_qcqp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_dense_qcqp_sol - { - struct s_dense_qcqp_dim *dim; - struct blasfeo_svec *v; - struct blasfeo_svec *pi; - struct blasfeo_svec *lam; - struct blasfeo_svec *t; - void *misc; - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_dense_qcqp_sol_memsize(struct s_dense_qcqp_dim *dim); -// -void s_dense_qcqp_sol_create(struct s_dense_qcqp_dim *dim, struct s_dense_qcqp_sol *qp_sol, void *memory); -// -void s_dense_qcqp_sol_get_v(struct s_dense_qcqp_sol *qp_sol, float *v); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_DENSE_QCQP_SOL_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_utils.h b/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_utils.h deleted file mode 100644 index 4f5aae26eb..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_utils.h +++ /dev/null @@ -1,83 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_DENSE_QCQP_UTILS_H_ -#define HPIPM_S_DENSE_QCQP_UTILS_H_ - - - -#include -#include - -#include "hpipm_s_dense_qcqp_dim.h" -#include "hpipm_s_dense_qcqp.h" -#include "hpipm_s_dense_qcqp_sol.h" -//#include "hpipm_s_dense_qcqp_ipm.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void s_dense_qcqp_dim_print(struct s_dense_qcqp_dim *qp_dim); -// -//void s_dense_qcqp_dim_codegen(char *file_name, char *mode, struct s_dense_qcqp_dim *qp_dim); -// -void s_dense_qcqp_print(struct s_dense_qcqp_dim *qp_dim, struct s_dense_qcqp *qp); -// -//void s_dense_qcqp_codegen(char *file_name, char *mode, struct s_dense_qcqp_dim *qp_dim, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_sol_print(struct s_dense_qcqp_dim *qp_dim, struct s_dense_qcqp_sol *dense_qcqp_sol); -// -//void s_dense_qcqp_ipm_arg_codegen(char *file_name, char *mode, struct s_dense_qcqp_dim *qp_dim, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_res_print(struct s_dense_qcqp_dim *qp_dim, struct s_dense_qcqp_res *dense_qcqp_res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_S_DENSE_QCQP_UTILS_H_ - - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_dense_qp.h b/third_party/acados/include/hpipm/include/hpipm_s_dense_qp.h deleted file mode 100644 index 3c2517fe1b..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_dense_qp.h +++ /dev/null @@ -1,207 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_S_DENSE_QP_H_ -#define HPIPM_S_DENSE_QP_H_ - - - -#include -#include - -#include "hpipm_s_dense_qp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_dense_qp - { - struct s_dense_qp_dim *dim; - struct blasfeo_smat *Hv; // hessian & gradient - struct blasfeo_smat *A; // dynamics matrix - struct blasfeo_smat *Ct; // constraints matrix - struct blasfeo_svec *gz; // gradient & gradient of slacks - struct blasfeo_svec *b; // dynamics vector - struct blasfeo_svec *d; // constraints vector - struct blasfeo_svec *d_mask; // inequality constraints mask vector - struct blasfeo_svec *m; // rhs of complementarity condition - struct blasfeo_svec *Z; // (diagonal) hessian of slacks - int *idxb; // indices of box constrained variables within [u; x] - int *idxs_rev; // index of soft constraints (reverse storage) - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t s_dense_qp_memsize(struct s_dense_qp_dim *dim); -// -void s_dense_qp_create(struct s_dense_qp_dim *dim, struct s_dense_qp *qp, void *memory); - -// setters - colmaj -// -void s_dense_qp_set_all(float *H, float *g, float *A, float *b, int *idxb, float *d_lb, float *d_ub, float *C, float *d_lg, float *d_ug, float *Zl, float *Zu, float *zl, float *zu, int *idxs, float *d_ls, float *d_us, struct s_dense_qp *qp); -// -void s_dense_qp_get_all(struct s_dense_qp *qp, float *H, float *g, float *A, float *b, int *idxb, float *d_lb, float *d_ub, float *C, float *d_lg, float *d_ug, float *Zl, float *Zu, float *zl, float *zu, int *idxs, float *d_ls, float *d_us); -// -void s_dense_qp_set(char *field, void *value, struct s_dense_qp *qp); -// -void s_dense_qp_set_H(float *H, struct s_dense_qp *qp); -// -void s_dense_qp_set_g(float *g, struct s_dense_qp *qp); -// -void s_dense_qp_set_A(float *A, struct s_dense_qp *qp); -// -void s_dense_qp_set_b(float *b, struct s_dense_qp *qp); -// -void s_dense_qp_set_idxb(int *idxb, struct s_dense_qp *qp); -// -void s_dense_qp_set_Jb(float *Jb, struct s_dense_qp *qp); -// -void s_dense_qp_set_lb(float *lb, struct s_dense_qp *qp); -// -void s_dense_qp_set_lb_mask(float *lb, struct s_dense_qp *qp); -// -void s_dense_qp_set_ub(float *ub, struct s_dense_qp *qp); -// -void s_dense_qp_set_ub_mask(float *ub, struct s_dense_qp *qp); -// -void s_dense_qp_set_C(float *C, struct s_dense_qp *qp); -// -void s_dense_qp_set_lg(float *lg, struct s_dense_qp *qp); -// -void s_dense_qp_set_lg_mask(float *lg, struct s_dense_qp *qp); -// -void s_dense_qp_set_ug(float *ug, struct s_dense_qp *qp); -// -void s_dense_qp_set_ug_mask(float *ug, struct s_dense_qp *qp); -// -void s_dense_qp_set_idxs(int *idxs, struct s_dense_qp *qp); -// -void s_dense_qp_set_idxs_rev(int *idxs_rev, struct s_dense_qp *qp); -// -void s_dense_qp_set_Jsb(float *Jsb, struct s_dense_qp *qp); -// -void s_dense_qp_set_Jsg(float *Jsg, struct s_dense_qp *qp); -// -void s_dense_qp_set_Zl(float *Zl, struct s_dense_qp *qp); -// -void s_dense_qp_set_Zu(float *Zu, struct s_dense_qp *qp); -// -void s_dense_qp_set_zl(float *zl, struct s_dense_qp *qp); -// -void s_dense_qp_set_zu(float *zu, struct s_dense_qp *qp); -// -void s_dense_qp_set_ls(float *ls, struct s_dense_qp *qp); -// -void s_dense_qp_set_ls_mask(float *ls, struct s_dense_qp *qp); -// -void s_dense_qp_set_us(float *us, struct s_dense_qp *qp); -// -void s_dense_qp_set_us_mask(float *us, struct s_dense_qp *qp); - -// getters - colmaj -// -void s_dense_qp_get_H(struct s_dense_qp *qp, float *H); -// -void s_dense_qp_get_g(struct s_dense_qp *qp, float *g); -// -void s_dense_qp_get_A(struct s_dense_qp *qp, float *A); -// -void s_dense_qp_get_b(struct s_dense_qp *qp, float *b); -// -void s_dense_qp_get_idxb(struct s_dense_qp *qp, int *idxb); -// -void s_dense_qp_get_lb(struct s_dense_qp *qp, float *lb); -// -void s_dense_qp_get_lb_mask(struct s_dense_qp *qp, float *lb); -// -void s_dense_qp_get_ub(struct s_dense_qp *qp, float *ub); -// -void s_dense_qp_get_ub_mask(struct s_dense_qp *qp, float *ub); -// -void s_dense_qp_get_C(struct s_dense_qp *qp, float *C); -// -void s_dense_qp_get_lg(struct s_dense_qp *qp, float *lg); -// -void s_dense_qp_get_lg_mask(struct s_dense_qp *qp, float *lg); -// -void s_dense_qp_get_ug(struct s_dense_qp *qp, float *ug); -// -void s_dense_qp_get_ug_mask(struct s_dense_qp *qp, float *ug); -// -void s_dense_qp_get_idxs(struct s_dense_qp *qp, int *idxs); -// -void s_dense_qp_get_idxs_rev(struct s_dense_qp *qp, int *idxs_rev); -// -void s_dense_qp_get_Zl(struct s_dense_qp *qp, float *Zl); -// -void s_dense_qp_get_Zu(struct s_dense_qp *qp, float *Zu); -// -void s_dense_qp_get_zl(struct s_dense_qp *qp, float *zl); -// -void s_dense_qp_get_zu(struct s_dense_qp *qp, float *zu); -// -void s_dense_qp_get_ls(struct s_dense_qp *qp, float *ls); -// -void s_dense_qp_get_ls_mask(struct s_dense_qp *qp, float *ls); -// -void s_dense_qp_get_us(struct s_dense_qp *qp, float *us); -// -void s_dense_qp_get_us_mask(struct s_dense_qp *qp, float *us); - -// setters - rowmaj -// -void s_dense_qp_set_all_rowmaj(float *H, float *g, float *A, float *b, int *idxb, float *d_lb, float *d_ub, float *C, float *d_lg, float *d_ug, float *Zl, float *Zu, float *zl, float *zu, int *idxs, float *d_ls, float *d_us, struct s_dense_qp *qp); - -// getters - rowmaj -// -void s_dense_qp_get_all_rowmaj(struct s_dense_qp *qp, float *H, float *g, float *A, float *b, int *idxb, float *d_lb, float *d_ub, float *C, float *d_lg, float *d_ug, float *Zl, float *Zu, float *zl, float *zu, int *idxs, float *d_ls, float *d_us); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_DENSE_QP_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_dim.h b/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_dim.h deleted file mode 100644 index b979d24432..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_dim.h +++ /dev/null @@ -1,94 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_DENSE_QP_DIM_H_ -#define HPIPM_S_DENSE_QP_DIM_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_dense_qp_dim - { - int nv; // number of variables - int ne; // number of equality constraints - int nb; // number of box constraints - int ng; // number of general constraints - int nsb; // number of softened box constraints - int nsg; // number of softened general constraints - int ns; // number of softened constraints (nsb+nsg) - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_dense_qp_dim_memsize(); -// -void s_dense_qp_dim_create(struct s_dense_qp_dim *qp_dim, void *memory); -// -void s_dense_qp_dim_set_all(int nv, int ne, int nb, int ng, int nsb, int nsg, struct s_dense_qp_dim *dim); -// -void s_dense_qp_dim_set(char *fiels_name, int value, struct s_dense_qp_dim *dim); -// -void s_dense_qp_dim_set_nv(int value, struct s_dense_qp_dim *dim); -// -void s_dense_qp_dim_set_ne(int value, struct s_dense_qp_dim *dim); -// -void s_dense_qp_dim_set_nb(int value, struct s_dense_qp_dim *dim); -// -void s_dense_qp_dim_set_ng(int value, struct s_dense_qp_dim *dim); -// -void s_dense_qp_dim_set_nsb(int value, struct s_dense_qp_dim *dim); -// -void s_dense_qp_dim_set_nsg(int value, struct s_dense_qp_dim *dim); -// -void s_dense_qp_dim_set_ns(int value, struct s_dense_qp_dim *dim); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_S_DENSE_QP_DIM_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_ipm.h b/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_ipm.h deleted file mode 100644 index f2d56d4529..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_ipm.h +++ /dev/null @@ -1,260 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_S_DENSE_QP_IPM_H_ -#define HPIPM_S_DENSE_QP_IPM_H_ - - - -#include -#include - -#include -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_dense_qp_ipm_arg - { - float mu0; // initial value for duality measure - float alpha_min; // exit cond on step length - float res_g_max; // exit cond on inf norm of residuals - float res_b_max; // exit cond on inf norm of residuals - float res_d_max; // exit cond on inf norm of residuals - float res_m_max; // exit cond on inf norm of residuals - float reg_prim; // reg of primal hessian - float reg_dual; // reg of dual hessian - float lam_min; // min value in lam vector - float t_min; // min value in t vector - float tau_min; // min value of barrier parameter - int iter_max; // exit cond in iter number - int stat_max; // iterations saved in stat - int pred_corr; // Mehrotra's predictor-corrector IPM algirthm - int cond_pred_corr; // conditional Mehrotra's predictor-corrector - int scale; // scale hessian - int itref_pred_max; // max number of iterative refinement steps for predictor step - int itref_corr_max; // max number of iterative refinement steps for corrector step - int warm_start; // 0 no warm start, 1 warm start primal sol, 2 warm start primal and dual sol - int lq_fact; // 0 syrk+potrf, 1 mix, 2 lq - int abs_form; // absolute IPM formulation - int comp_res_exit; // compute residuals on exit (only for abs_form==1) - int comp_res_pred; // compute residuals of prediction - int kkt_fact_alg; // 0 null-space, 1 schur-complement - int remove_lin_dep_eq; // 0 do not, 1 do check and remove linearly dependent equality constraints - int compute_obj; // compute obj on exit - int split_step; // use different steps for primal and dual variables - int t_lam_min; // clip t and lam: 0 no, 1 in Gamma computation, 2 in solution - int mode; - hpipm_size_t memsize; - }; - - - -struct s_dense_qp_ipm_ws - { - struct s_core_qp_ipm_workspace *core_workspace; - struct s_dense_qp_res_ws *res_ws; - struct s_dense_qp_sol *sol_step; - struct s_dense_qp_sol *sol_itref; - struct s_dense_qp *qp_step; - struct s_dense_qp *qp_itref; - struct s_dense_qp_res *res; - struct s_dense_qp_res *res_itref; - struct s_dense_qp_res *res_step; - struct blasfeo_svec *Gamma; // - struct blasfeo_svec *gamma; // - struct blasfeo_svec *Zs_inv; // - struct blasfeo_smat *Lv; // - struct blasfeo_smat *AL; // - struct blasfeo_smat *Le; // - struct blasfeo_smat *Ctx; // - struct blasfeo_svec *lv; // - struct blasfeo_svec *sv; // scale for Lv - struct blasfeo_svec *se; // scale for Le - struct blasfeo_svec *tmp_nbg; // work space of size nb+ng - struct blasfeo_svec *tmp_ns; // work space of size ns - struct blasfeo_smat *lq0; - struct blasfeo_smat *lq1; - struct blasfeo_svec *tmp_m; - struct blasfeo_smat *A_LQ; - struct blasfeo_smat *A_Q; - struct blasfeo_smat *Zt; - struct blasfeo_smat *ZtH; - struct blasfeo_smat *ZtHZ; - struct blasfeo_svec *xy; - struct blasfeo_svec *Yxy; - struct blasfeo_svec *xz; - struct blasfeo_svec *tmp_nv; - struct blasfeo_svec *tmp_2ns; - struct blasfeo_svec *tmp_nv2ns; - struct blasfeo_smat *A_li; // A of linearly independent equality constraints - struct blasfeo_svec *b_li; // b of linearly independent equality constraints - struct blasfeo_smat *A_bkp; // pointer to backup A - struct blasfeo_svec *b_bkp; // pointer to backup b - struct blasfeo_smat *Ab_LU; - float *stat; // convergence statistics - int *ipiv_v; - int *ipiv_e; - int *ipiv_e1; - void *lq_work0; - void *lq_work1; - void *lq_work_null; - void *orglq_work_null; - int iter; // iteration number - int stat_max; // iterations saved in stat - int stat_m; // numer of recorded stat per ipm iter - int scale; - int use_hess_fact; - int use_A_fact; - int status; - int lq_fact; // cache from arg - int mask_constr; // use constr mask - int ne_li; // number of linearly independent equality constraints - int ne_bkp; // ne backup - hpipm_size_t memsize; // memory size (in bytes) of workspace - }; - - - -// -hpipm_size_t s_dense_qp_ipm_arg_memsize(struct s_dense_qp_dim *qp_dim); -// -void s_dense_qp_ipm_arg_create(struct s_dense_qp_dim *qp_dim, struct s_dense_qp_ipm_arg *arg, void *mem); -// -void s_dense_qp_ipm_arg_set_default(enum hpipm_mode mode, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set(char *field, void *value, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_iter_max(int *iter_max, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_alpha_min(float *alpha_min, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_mu0(float *mu0, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_tol_stat(float *tol_stat, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_tol_eq(float *tol_eq, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_tol_ineq(float *tol_ineq, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_tol_comp(float *tol_comp, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_reg_prim(float *reg, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_reg_dual(float *reg, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_warm_start(int *warm_start, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_pred_corr(int *pred_corr, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_cond_pred_corr(int *cond_pred_corr, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_comp_res_pred(int *comp_res_pred, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_comp_res_exit(int *comp_res_exit, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_lam_min(float *value, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_t_min(float *value, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_tau_min(float *value, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_kkt_fact_alg(int *value, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_remove_lin_dep_eq(int *value, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_compute_obj(int *value, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_split_step(int *value, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_t_lam_min(int *value, struct s_dense_qp_ipm_arg *arg); - -// -hpipm_size_t s_dense_qp_ipm_ws_memsize(struct s_dense_qp_dim *qp_dim, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_ws_create(struct s_dense_qp_dim *qp_dim, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws, void *mem); -// -void s_dense_qp_ipm_get(char *field, struct s_dense_qp_ipm_ws *ws, void *value); -// -void s_dense_qp_ipm_get_status(struct s_dense_qp_ipm_ws *ws, int *status); -// -void s_dense_qp_ipm_get_iter(struct s_dense_qp_ipm_ws *ws, int *iter); -// -void s_dense_qp_ipm_get_max_res_stat(struct s_dense_qp_ipm_ws *ws, float *res_stat); -// -void s_dense_qp_ipm_get_max_res_eq(struct s_dense_qp_ipm_ws *ws, float *res_eq); -// -void s_dense_qp_ipm_get_max_res_ineq(struct s_dense_qp_ipm_ws *ws, float *res_ineq); -// -void s_dense_qp_ipm_get_max_res_comp(struct s_dense_qp_ipm_ws *ws, float *res_comp); -// -void s_dense_qp_ipm_get_stat(struct s_dense_qp_ipm_ws *ws, float **stat); -// -void s_dense_qp_ipm_get_stat_m(struct s_dense_qp_ipm_ws *ws, int *stat_m); -// -void s_dense_qp_init_var(struct s_dense_qp *qp, struct s_dense_qp_sol *qp_sol, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws); -// -void s_dense_qp_ipm_abs_step(int kk, struct s_dense_qp *qp, struct s_dense_qp_sol *qp_sol, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws); -// -void s_dense_qp_ipm_delta_step(int kk, struct s_dense_qp *qp, struct s_dense_qp_sol *qp_sol, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws); -// -void s_dense_qp_ipm_solve(struct s_dense_qp *qp, struct s_dense_qp_sol *qp_sol, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws); -// -void s_dense_qp_ipm_predict(struct s_dense_qp *qp, struct s_dense_qp_sol *qp_sol, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws); -// -void s_dense_qp_ipm_sens(struct s_dense_qp *qp, struct s_dense_qp_sol *qp_sol, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws); -// -void s_dense_qp_compute_step_length(struct s_dense_qp *qp, struct s_dense_qp_sol *qp_sol, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_DENSE_QP_IPM_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_kkt.h b/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_kkt.h deleted file mode 100644 index 260dc0ab21..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_kkt.h +++ /dev/null @@ -1,72 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_S_DENSE_QP_KKT_H_ -#define HPIPM_S_DENSE_QP_KKT_H_ - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void s_fact_solve_kkt_unconstr_dense_qp(struct s_dense_qp *qp, struct s_dense_qp_sol *qp_sol, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws); -// -void s_fact_solve_kkt_step_dense_qp(struct s_dense_qp *qp, struct s_dense_qp_sol *qp_sol, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws); -// -void s_fact_lq_solve_kkt_step_dense_qp(struct s_dense_qp *qp, struct s_dense_qp_sol *qp_sol, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws); -// -void s_solve_kkt_step_dense_qp(struct s_dense_qp *qp, struct s_dense_qp_sol *qp_sol, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws); -// -void s_dense_qp_remove_lin_dep_eq(struct s_dense_qp *qp, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws); -// -void s_dense_qp_restore_lin_dep_eq(struct s_dense_qp *qp, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws); -// -void s_dense_qp_compute_obj(struct s_dense_qp *qp, struct s_dense_qp_sol *qp_sol, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_DENSE_QP_KKT_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_res.h b/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_res.h deleted file mode 100644 index 06b609c537..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_res.h +++ /dev/null @@ -1,106 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_DENSE_QP_RES_H_ -#define HPIPM_S_DENSE_QP_RES_H_ - - - -#include -#include - -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_dense_qp_res - { - struct s_dense_qp_dim *dim; - struct blasfeo_svec *res_g; // q-residuals - struct blasfeo_svec *res_b; // b-residuals - struct blasfeo_svec *res_d; // d-residuals - struct blasfeo_svec *res_m; // m-residuals - float res_max[4]; // max of residuals - float res_mu; // mu-residual - hpipm_size_t memsize; - }; - - - -struct s_dense_qp_res_ws - { - struct blasfeo_svec *tmp_nbg; // work space of size nbM+ngM - struct blasfeo_svec *tmp_ns; // work space of size nsM - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_dense_qp_res_memsize(struct s_dense_qp_dim *dim); -// -void s_dense_qp_res_create(struct s_dense_qp_dim *dim, struct s_dense_qp_res *res, void *mem); -// -hpipm_size_t s_dense_qp_res_ws_memsize(struct s_dense_qp_dim *dim); -// -void s_dense_qp_res_ws_create(struct s_dense_qp_dim *dim, struct s_dense_qp_res_ws *workspace, void *mem); -// -void s_dense_qp_res_compute(struct s_dense_qp *qp, struct s_dense_qp_sol *qp_sol, struct s_dense_qp_res *res, struct s_dense_qp_res_ws *ws); -// -void s_dense_qp_res_compute_lin(struct s_dense_qp *qp, struct s_dense_qp_sol *qp_sol, struct s_dense_qp_sol *qp_step, struct s_dense_qp_res *res, struct s_dense_qp_res_ws *ws); -// -void s_dense_qp_res_compute_inf_norm(struct s_dense_qp_res *res); -// -void s_dense_qp_res_get_all(struct s_dense_qp_res *res, float *res_g, float *res_ls, float *res_us, float *res_b, float *res_d_lb, float *res_d_ub, float *res_d_lg, float *res_d_ug, float *res_d_ls, float *res_d_us, float *res_m_lb, float *res_m_ub, float *res_m_lg, float *res_m_ug, float *res_m_ls, float *res_m_us); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_D_DENSE_QP_RES_H_ - - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_sol.h b/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_sol.h deleted file mode 100644 index 1f40076378..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_sol.h +++ /dev/null @@ -1,94 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_S_DENSE_QP_SOL_H_ -#define HPIPM_S_DENSE_QP_SOL_H_ - - - -#include -#include - -#include "hpipm_s_dense_qp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_dense_qp_sol - { - struct s_dense_qp_dim *dim; - struct blasfeo_svec *v; - struct blasfeo_svec *pi; - struct blasfeo_svec *lam; - struct blasfeo_svec *t; - void *misc; - float obj; - int valid_obj; - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_dense_qp_sol_memsize(struct s_dense_qp_dim *dim); -// -void s_dense_qp_sol_create(struct s_dense_qp_dim *dim, struct s_dense_qp_sol *qp_sol, void *memory); -// -void s_dense_qp_sol_get_all(struct s_dense_qp_sol *qp_sol, float *v, float *ls, float *us, float *pi, float *lam_lb, float *lam_ub, float *lam_lg, float *lam_ug, float *lam_ls, float *lam_us); -// -void s_dense_qp_sol_get(char *field, struct s_dense_qp_sol *sol, void *value); -// -void s_dense_qp_sol_get_v(struct s_dense_qp_sol *sol, float *v); -// -void s_dense_qp_sol_get_valid_obj(struct s_dense_qp_sol *sol, int *valid_obj); -// -void s_dense_qp_sol_get_obj(struct s_dense_qp_sol *sol, float *obj); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_DENSE_QP_SOL_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_utils.h b/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_utils.h deleted file mode 100644 index 3dd93259a5..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_utils.h +++ /dev/null @@ -1,84 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_DENSE_QP_UTILS_H_ -#define HPIPM_S_DENSE_QP_UTILS_H_ - - - -#include -#include - -#include "hpipm_s_dense_qp_dim.h" -#include "hpipm_s_dense_qp.h" -#include "hpipm_s_dense_qp_sol.h" -#include "hpipm_s_dense_qp_ipm.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void s_dense_qp_dim_print(struct s_dense_qp_dim *qp_dim); -// -//void s_dense_qp_dim_codegen(char *file_name, char *mode, struct s_dense_qp_dim *qp_dim); -// -void s_dense_qp_print(struct s_dense_qp_dim *qp_dim, struct s_dense_qp *qp); -// -//void s_dense_qp_codegen(char *file_name, char *mode, struct s_dense_qp_dim *qp_dim, struct s_dense_qp *qp); -// -void s_dense_qp_sol_print(struct s_dense_qp_dim *qp_dim, struct s_dense_qp_sol *dense_qp_sol); -// -//void s_dense_qp_ipm_arg_codegen(char *file_name, char *mode, struct s_dense_qp_dim *qp_dim, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_res_print(struct s_dense_qp_dim *qp_dim, struct s_dense_qp_res *dense_qp_res); -// -void s_dense_qp_arg_print(struct s_dense_qp_dim *qp_dim, struct s_dense_qp_ipm_arg *qp_ipm_arg); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_S_DENSE_QP_UTILS_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp.h b/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp.h deleted file mode 100644 index b90b2ac633..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp.h +++ /dev/null @@ -1,303 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_OCP_QCQP_H_ -#define HPIPM_S_OCP_QCQP_H_ - - - -#include -#include - -#include "hpipm_s_ocp_qcqp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_ocp_qcqp - { - struct s_ocp_qcqp_dim *dim; - struct blasfeo_smat *BAbt; // dynamics matrix & vector work space - struct blasfeo_smat *RSQrq; // hessian of cost & vector work space - struct blasfeo_smat *DCt; // inequality constraints matrix - struct blasfeo_smat **Hq; // hessians of quadratic constraints - struct blasfeo_svec *b; // dynamics vector - struct blasfeo_svec *rqz; // gradient of cost & gradient of slacks - struct blasfeo_svec *d; // inequality constraints vector - struct blasfeo_svec *d_mask; // inequality constraints mask vector - struct blasfeo_svec *m; // rhs of complementarity condition - struct blasfeo_svec *Z; // (diagonal) hessian of slacks - int **idxb; // indices of box constrained variables within [u; x] - int **idxs_rev; // index of soft constraints (reverse storage) - int **Hq_nzero; // for each int, the last 3 bits ...abc, {a,b,c}=0 => {R,S,Q}=0 - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t s_ocp_qcqp_strsize(); -// -hpipm_size_t s_ocp_qcqp_memsize(struct s_ocp_qcqp_dim *dim); -// -void s_ocp_qcqp_create(struct s_ocp_qcqp_dim *dim, struct s_ocp_qcqp *qp, void *memory); -// -void s_ocp_qcqp_copy_all(struct s_ocp_qcqp *qp_orig, struct s_ocp_qcqp *qp_dest); - -// setters -// -void s_ocp_qcqp_set_all_zero(struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_rhs_zero(struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set(char *fiels_name, int stage, void *value, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_el(char *fiels_name, int stage, int index, void *value, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_A(int stage, float *mat, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_B(int stage, float *mat, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_b(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_Q(int stage, float *mat, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_S(int stage, float *mat, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_R(int stage, float *mat, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_q(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_r(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_lb(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_lb_mask(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_ub(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_ub_mask(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_lbx(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_lbx_mask(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_el_lbx(int stage, int index, float *elem, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_ubx(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_ubx_mask(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_el_ubx(int stage, int index, float *elem, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_lbu(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_lbu_mask(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_ubu(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_ubu_mask(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_idxb(int stage, int *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_idxbx(int stage, int *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_Jbx(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_idxbu(int stage, int *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_Jbu(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_C(int stage, float *mat, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_D(int stage, float *mat, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_lg(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_lg_mask(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_ug(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_ug_mask(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_Qq(int stage, float *mat, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_Sq(int stage, float *mat, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_Rq(int stage, float *mat, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_qq(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_rq(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_uq(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_uq_mask(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_Zl(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_Zu(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_zl(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_zu(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_lls(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_lls_mask(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_lus(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_lus_mask(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_idxs(int stage, int *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_idxs_rev(int stage, int *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_Jsbu(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_Jsbx(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_Jsg(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_Jsq(int stage, float *vec, struct s_ocp_qcqp *qp); - -// getters -// -void s_ocp_qcqp_get(char *field, int stage, struct s_ocp_qcqp *qp, void *value); -// -void s_ocp_qcqp_get_A(int stage, struct s_ocp_qcqp *qp, float *mat); -// -void s_ocp_qcqp_get_B(int stage, struct s_ocp_qcqp *qp, float *mat); -// -void s_ocp_qcqp_get_b(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_Q(int stage, struct s_ocp_qcqp *qp, float *mat); -// -void s_ocp_qcqp_get_S(int stage, struct s_ocp_qcqp *qp, float *mat); -// -void s_ocp_qcqp_get_R(int stage, struct s_ocp_qcqp *qp, float *mat); -// -void s_ocp_qcqp_get_q(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_r(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_ub(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_ub_mask(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_lb(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_lb_mask(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_lbx(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_lbx_mask(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_ubx(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_ubx_mask(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_lbu(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_lbu_mask(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_ubu(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_ubu_mask(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_idxb(int stage, struct s_ocp_qcqp *qp, int *vec); -// -//void s_ocp_qcqp_get_idxbx(int stage, struct s_ocp_qcqp *qp, int *vec); -// -//void s_ocp_qcqp_get_Jbx(int stage, struct s_ocp_qcqp *qp, float *vec); -// -//void s_ocp_qcqp_get_idxbu(int stage, struct s_ocp_qcqp *qp, int *vec); -// -//void s_ocp_qcqp_get_Jbu(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_C(int stage, struct s_ocp_qcqp *qp, float *mat); -// -void s_ocp_qcqp_get_D(int stage, struct s_ocp_qcqp *qp, float *mat); -// -void s_ocp_qcqp_get_lg(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_lg_mask(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_ug(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_ug_mask(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_Zl(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_Zu(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_zl(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_zu(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_lls(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_lls_mask(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_lus(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_lus_mask(int stage, struct s_ocp_qcqp *qp, float *vec); -// XXX only valid if there is one slack per softed constraint !!! -void s_ocp_qcqp_get_idxs(int stage, struct s_ocp_qcqp *qp, int *vec); -// -void s_ocp_qcqp_get_idxs_rev(int stage, struct s_ocp_qcqp *qp, int *vec); -// -//void s_ocp_qcqp_get_Jsbu(int stage, struct s_ocp_qcqp *qp, float *vec); -// -//void s_ocp_qcqp_get_Jsbx(int stage, struct s_ocp_qcqp *qp, float *vec); -// -//void s_ocp_qcqp_get_Jsg(int stage, struct s_ocp_qcqp *qp, float *vec); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_OCP_QCQP_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_dim.h b/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_dim.h deleted file mode 100644 index c09903f074..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_dim.h +++ /dev/null @@ -1,119 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_OCP_QCQP_DIM_H_ -#define HPIPM_S_OCP_QCQP_DIM_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_ocp_qcqp_dim - { - struct s_ocp_qp_dim *qp_dim; // dim of qp approximation - int *nx; // number of states - int *nu; // number of inputs - int *nb; // number of box constraints - int *nbx; // number of (two-sided) state box constraints - int *nbu; // number of (two-sided) input box constraints - int *ng; // number of (two-sided) general constraints - int *nq; // number of (upper) quadratic constraints - int *ns; // number of soft constraints - int *nsbx; // number of (two-sided) soft state box constraints - int *nsbu; // number of (two-sided) soft input box constraints - int *nsg; // number of (two-sided) soft general constraints - int *nsq; // number of (upper) soft quadratic constraints - int N; // horizon length - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_ocp_qcqp_dim_strsize(); -// -hpipm_size_t s_ocp_qcqp_dim_memsize(int N); -// -void s_ocp_qcqp_dim_create(int N, struct s_ocp_qcqp_dim *qp_dim, void *memory); -// -void s_ocp_qcqp_dim_copy_all(struct s_ocp_qcqp_dim *dim_orig, struct s_ocp_qcqp_dim *dim_dest); -// -void s_ocp_qcqp_dim_set(char *field, int stage, int value, struct s_ocp_qcqp_dim *dim); -// -void s_ocp_qcqp_dim_set_nx(int stage, int value, struct s_ocp_qcqp_dim *dim); -// -void s_ocp_qcqp_dim_set_nu(int stage, int value, struct s_ocp_qcqp_dim *dim); -// -void s_ocp_qcqp_dim_set_nbx(int stage, int value, struct s_ocp_qcqp_dim *dim); -// -void s_ocp_qcqp_dim_set_nbu(int stage, int value, struct s_ocp_qcqp_dim *dim); -// -void s_ocp_qcqp_dim_set_ng(int stage, int value, struct s_ocp_qcqp_dim *dim); -// -void s_ocp_qcqp_dim_set_nq(int stage, int value, struct s_ocp_qcqp_dim *dim); -// -void s_ocp_qcqp_dim_set_ns(int stage, int value, struct s_ocp_qcqp_dim *dim); -// -void s_ocp_qcqp_dim_set_nsbx(int stage, int value, struct s_ocp_qcqp_dim *dim); -// -void s_ocp_qcqp_dim_set_nsbu(int stage, int value, struct s_ocp_qcqp_dim *dim); -// -void s_ocp_qcqp_dim_set_nsg(int stage, int value, struct s_ocp_qcqp_dim *dim); -// -void s_ocp_qcqp_dim_set_nsq(int stage, int value, struct s_ocp_qcqp_dim *dim); -// -void s_ocp_qcqp_dim_get(struct s_ocp_qcqp_dim *dim, char *field, int stage, int *value); -// -void s_ocp_qcqp_dim_get_N(struct s_ocp_qcqp_dim *dim, int *value); -// -void s_ocp_qcqp_dim_get_nx(struct s_ocp_qcqp_dim *dim, int stage, int *value); -// -void s_ocp_qcqp_dim_get_nu(struct s_ocp_qcqp_dim *dim, int stage, int *value); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_S_OCP_QCQP_DIM_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_ipm.h b/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_ipm.h deleted file mode 100644 index c14fc1c9fd..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_ipm.h +++ /dev/null @@ -1,191 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_OCP_QCQP_IPM_H_ -#define HPIPM_S_OCP_QCQP_IPM_H_ - - - -#include -#include - -#include -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_ocp_qcqp_ipm_arg - { - struct s_ocp_qp_ipm_arg *qp_arg; - float mu0; // initial value for complementarity slackness - float alpha_min; // exit cond on step length - float res_g_max; // exit cond on inf norm of residuals - float res_b_max; // exit cond on inf norm of residuals - float res_d_max; // exit cond on inf norm of residuals - float res_m_max; // exit cond on inf norm of residuals - float reg_prim; // reg of primal hessian - float lam_min; // min value in lam vector - float t_min; // min value in t vector - int iter_max; // exit cond in iter number - int stat_max; // iterations saved in stat - int pred_corr; // use Mehrotra's predictor-corrector IPM algirthm - int cond_pred_corr; // conditional Mehrotra's predictor-corrector - int itref_pred_max; // max number of iterative refinement steps for predictor step - int itref_corr_max; // max number of iterative refinement steps for corrector step - int warm_start; // 0 no warm start, 1 warm start primal sol, 2 warm start primal and dual sol - int square_root_alg; // 0 classical Riccati, 1 square-root Riccati - int lq_fact; // 0 syrk+potrf, 1 mix, 2 lq (for square_root_alg==1) - int abs_form; // absolute IPM formulation - int comp_dual_sol_eq; // dual solution of equality constraints (only for abs_form==1) - int comp_res_exit; // compute residuals on exit (only for abs_form==1 and comp_dual_sol_eq==1) - int comp_res_pred; // compute residuals of prediction - int split_step; // use different step for primal and dual variables - int t_lam_min; // clip t and lam: 0 no, 1 in Gamma computation, 2 in solution - int mode; - hpipm_size_t memsize; - }; - - - -struct s_ocp_qcqp_ipm_ws - { - struct s_ocp_qp_ipm_ws *qp_ws; - struct s_ocp_qp *qp; - struct s_ocp_qp_sol *qp_sol; - struct s_ocp_qcqp_res_ws *qcqp_res_ws; - struct s_ocp_qcqp_res *qcqp_res; - struct blasfeo_svec *tmp_nuxM; - int iter; // iteration number - int status; - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_ocp_qcqp_ipm_arg_strsize(); -// -hpipm_size_t s_ocp_qcqp_ipm_arg_memsize(struct s_ocp_qcqp_dim *ocp_dim); -// -void s_ocp_qcqp_ipm_arg_create(struct s_ocp_qcqp_dim *ocp_dim, struct s_ocp_qcqp_ipm_arg *arg, void *mem); -// -void s_ocp_qcqp_ipm_arg_set_default(enum hpipm_mode mode, struct s_ocp_qcqp_ipm_arg *arg); -// -void s_ocp_qcqp_ipm_arg_set(char *field, void *value, struct s_ocp_qcqp_ipm_arg *arg); -// set maximum number of iterations -void s_ocp_qcqp_ipm_arg_set_iter_max(int *value, struct s_ocp_qcqp_ipm_arg *arg); -// set minimum step lenght -void s_ocp_qcqp_ipm_arg_set_alpha_min(float *value, struct s_ocp_qcqp_ipm_arg *arg); -// set initial value of barrier parameter -void s_ocp_qcqp_ipm_arg_set_mu0(float *value, struct s_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on stationarity condition -void s_ocp_qcqp_ipm_arg_set_tol_stat(float *value, struct s_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on equality constr -void s_ocp_qcqp_ipm_arg_set_tol_eq(float *value, struct s_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on inequality constr -void s_ocp_qcqp_ipm_arg_set_tol_ineq(float *value, struct s_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on complementarity condition -void s_ocp_qcqp_ipm_arg_set_tol_comp(float *value, struct s_ocp_qcqp_ipm_arg *arg); -// set regularization of primal variables -void s_ocp_qcqp_ipm_arg_set_reg_prim(float *value, struct s_ocp_qcqp_ipm_arg *arg); -// set warm start: 0 no warm start, 1 primal var -void s_ocp_qcqp_ipm_arg_set_warm_start(int *value, struct s_ocp_qcqp_ipm_arg *arg); -// Mehrotra's predictor-corrector IPM algorithm: 0 no predictor-corrector, 1 use predictor-corrector -void s_ocp_qcqp_ipm_arg_set_pred_corr(int *value, struct s_ocp_qcqp_ipm_arg *arg); -// conditional predictor-corrector: 0 no conditinal predictor-corrector, 1 conditional predictor-corrector -void s_ocp_qcqp_ipm_arg_set_cond_pred_corr(int *value, struct s_ocp_qcqp_ipm_arg *arg); -// set riccati algorithm: 0 classic, 1 square-root -void s_ocp_qcqp_ipm_arg_set_ric_alg(int *value, struct s_ocp_qcqp_ipm_arg *arg); -// compute residuals after solution -void s_ocp_qcqp_ipm_arg_set_comp_res_exit(int *value, struct s_ocp_qcqp_ipm_arg *arg); -// compute residuals of prediction -void s_ocp_qcqp_ipm_arg_set_comp_res_pred(int *value, struct s_ocp_qcqp_ipm_arg *arg); -// min value of lam in the solution -void s_ocp_qcqp_ipm_arg_set_lam_min(float *value, struct s_ocp_qcqp_ipm_arg *arg); -// min value of t in the solution -void s_ocp_qcqp_ipm_arg_set_t_min(float *value, struct s_ocp_qcqp_ipm_arg *arg); -// use different step for primal and dual variables -void s_ocp_qcqp_ipm_arg_set_split_step(int *value, struct s_ocp_qcqp_ipm_arg *arg); -// clip t and lam: 0 no, 1 in Gamma computation, 2 in solution -void s_ocp_qcqp_ipm_arg_set_t_lam_min(int *value, struct s_ocp_qcqp_ipm_arg *arg); - -// -hpipm_size_t s_ocp_qcqp_ipm_ws_strsize(); -// -hpipm_size_t s_ocp_qcqp_ipm_ws_memsize(struct s_ocp_qcqp_dim *ocp_dim, struct s_ocp_qcqp_ipm_arg *arg); -// -void s_ocp_qcqp_ipm_ws_create(struct s_ocp_qcqp_dim *ocp_dim, struct s_ocp_qcqp_ipm_arg *arg, struct s_ocp_qcqp_ipm_ws *ws, void *mem); -// -void s_ocp_qcqp_ipm_get(char *field, struct s_ocp_qcqp_ipm_ws *ws, void *value); -// -void s_ocp_qcqp_ipm_get_status(struct s_ocp_qcqp_ipm_ws *ws, int *status); -// -void s_ocp_qcqp_ipm_get_iter(struct s_ocp_qcqp_ipm_ws *ws, int *iter); -// -void s_ocp_qcqp_ipm_get_max_res_stat(struct s_ocp_qcqp_ipm_ws *ws, float *res_stat); -// -void s_ocp_qcqp_ipm_get_max_res_eq(struct s_ocp_qcqp_ipm_ws *ws, float *res_eq); -// -void s_ocp_qcqp_ipm_get_max_res_ineq(struct s_ocp_qcqp_ipm_ws *ws, float *res_ineq); -// -void s_ocp_qcqp_ipm_get_max_res_comp(struct s_ocp_qcqp_ipm_ws *ws, float *res_comp); -// -void s_ocp_qcqp_ipm_get_stat(struct s_ocp_qcqp_ipm_ws *ws, float **stat); -// -void s_ocp_qcqp_ipm_get_stat_m(struct s_ocp_qcqp_ipm_ws *ws, int *stat_m); -// -void s_ocp_qcqp_init_var(struct s_ocp_qcqp *qp, struct s_ocp_qcqp_sol *qp_sol, struct s_ocp_qcqp_ipm_arg *arg, struct s_ocp_qcqp_ipm_ws *ws); -// -void s_ocp_qcqp_ipm_solve(struct s_ocp_qcqp *qp, struct s_ocp_qcqp_sol *qp_sol, struct s_ocp_qcqp_ipm_arg *arg, struct s_ocp_qcqp_ipm_ws *ws); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_S_OCP_QCQP_IPM_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_res.h b/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_res.h deleted file mode 100644 index 1ceeec93b7..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_res.h +++ /dev/null @@ -1,115 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_OCP_QCQP_RES_H_ -#define HPIPM_S_OCP_QCQP_RES_H_ - - - -#include -#include - -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_ocp_qcqp_res - { - struct s_ocp_qcqp_dim *dim; - struct blasfeo_svec *res_g; // q-residuals - struct blasfeo_svec *res_b; // b-residuals - struct blasfeo_svec *res_d; // d-residuals - struct blasfeo_svec *res_m; // m-residuals - float res_max[4]; // max of residuals - float res_mu; // mu-residual - hpipm_size_t memsize; - }; - - - -struct s_ocp_qcqp_res_ws - { - struct blasfeo_svec *tmp_nuxM; // work space of size nuM+nxM - struct blasfeo_svec *tmp_nbgqM; // work space of size nbM+ngM+nqM - struct blasfeo_svec *tmp_nsM; // work space of size nsM - struct blasfeo_svec *q_fun; // value for evaluation of quadr constr - struct blasfeo_svec *q_adj; // value for adjoint of quadr constr - int use_q_fun; // reuse cached value for evaluation of quadr constr - int use_q_adj; // reuse cached value for adjoint of quadr constr - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_ocp_qcqp_res_memsize(struct s_ocp_qcqp_dim *ocp_dim); -// -void s_ocp_qcqp_res_create(struct s_ocp_qcqp_dim *ocp_dim, struct s_ocp_qcqp_res *res, void *mem); -// -hpipm_size_t s_ocp_qcqp_res_ws_memsize(struct s_ocp_qcqp_dim *ocp_dim); -// -void s_ocp_qcqp_res_ws_create(struct s_ocp_qcqp_dim *ocp_dim, struct s_ocp_qcqp_res_ws *workspace, void *mem); -// -void s_ocp_qcqp_res_compute(struct s_ocp_qcqp *qp, struct s_ocp_qcqp_sol *qp_sol, struct s_ocp_qcqp_res *res, struct s_ocp_qcqp_res_ws *ws); -// -void s_ocp_qcqp_res_compute_inf_norm(struct s_ocp_qcqp_res *res); -// -void s_ocp_qcqp_res_get_max_res_stat(struct s_ocp_qcqp_res *res, float *value); -// -void s_ocp_qcqp_res_get_max_res_eq(struct s_ocp_qcqp_res *res, float *value); -// -void s_ocp_qcqp_res_get_max_res_ineq(struct s_ocp_qcqp_res *res, float *value); -// -void s_ocp_qcqp_res_get_max_res_comp(struct s_ocp_qcqp_res *res, float *value); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_S_OCP_QCQP_RES_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_sol.h b/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_sol.h deleted file mode 100644 index 3d58022cc9..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_sol.h +++ /dev/null @@ -1,115 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_OCP_QCQP_SOL_H_ -#define HPIPM_S_OCP_QCQP_SOL_H_ - - - -#include -#include - -#include "hpipm_s_ocp_qcqp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_ocp_qcqp_sol - { - struct s_ocp_qcqp_dim *dim; - struct blasfeo_svec *ux; - struct blasfeo_svec *pi; - struct blasfeo_svec *lam; - struct blasfeo_svec *t; - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t s_ocp_qcqp_sol_strsize(); -// -hpipm_size_t s_ocp_qcqp_sol_memsize(struct s_ocp_qcqp_dim *dim); -// -void s_ocp_qcqp_sol_create(struct s_ocp_qcqp_dim *dim, struct s_ocp_qcqp_sol *qp_sol, void *memory); -// -void s_ocp_qcqp_sol_copy_all(struct s_ocp_qcqp_sol *qp_sol_orig, struct s_ocp_qcqp_sol *qp_sol_dest); -// -void s_ocp_qcqp_sol_get(char *field, int stage, struct s_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_ocp_qcqp_sol_get_u(int stage, struct s_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_ocp_qcqp_sol_get_x(int stage, struct s_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_ocp_qcqp_sol_get_sl(int stage, struct s_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_ocp_qcqp_sol_get_su(int stage, struct s_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_ocp_qcqp_sol_get_pi(int stage, struct s_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_ocp_qcqp_sol_get_lam_lb(int stage, struct s_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_ocp_qcqp_sol_get_lam_ub(int stage, struct s_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_ocp_qcqp_sol_get_lam_lg(int stage, struct s_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_ocp_qcqp_sol_get_lam_ug(int stage, struct s_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_ocp_qcqp_sol_set(char *field, int stage, float *vec, struct s_ocp_qcqp_sol *qp_sol); -// -void s_ocp_qcqp_sol_set_u(int stage, float *vec, struct s_ocp_qcqp_sol *qp_sol); -// -void s_ocp_qcqp_sol_set_x(int stage, float *vec, struct s_ocp_qcqp_sol *qp_sol); -// -void s_ocp_qcqp_sol_set_sl(int stage, float *vec, struct s_ocp_qcqp_sol *qp_sol); -// -void s_ocp_qcqp_sol_set_su(int stage, float *vec, struct s_ocp_qcqp_sol *qp_sol); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_S_OCP_QCQP_SOL_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_utils.h b/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_utils.h deleted file mode 100644 index d64e3aabe7..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_utils.h +++ /dev/null @@ -1,82 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_OCP_QCQP_UTILS_H_ -#define HPIPM_S_OCP_QCQP_UTILS_H_ - - - -#include -#include - -#include "hpipm_s_ocp_qcqp_dim.h" -#include "hpipm_s_ocp_qp.h" -#include "hpipm_s_ocp_qcqp_sol.h" -#include "hpipm_s_ocp_qcqp_ipm.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void s_ocp_qcqp_dim_print(struct s_ocp_qcqp_dim *qcqp_dim); -// -void s_ocp_qcqp_dim_codegen(char *file_name, char *mode, struct s_ocp_qcqp_dim *qcqp_dim); -// -void s_ocp_qcqp_print(struct s_ocp_qcqp_dim *qcqp_dim, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_codegen(char *file_name, char *mode, struct s_ocp_qcqp_dim *qcqp_dim, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_sol_print(struct s_ocp_qcqp_dim *qcqp_dim, struct s_ocp_qcqp_sol *ocp_qcqp_sol); -// -void s_ocp_qcqp_ipm_arg_codegen(char *file_name, char *mode, struct s_ocp_qcqp_dim *qcqp_dim, struct s_ocp_qcqp_ipm_arg *arg); -// -void s_ocp_qcqp_res_print(struct s_ocp_qcqp_dim *qcqp_dim, struct s_ocp_qcqp_res *ocp_qcqp_res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_S_OCP_QCQP_UTILS_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp.h b/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp.h deleted file mode 100644 index b49191f192..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp.h +++ /dev/null @@ -1,306 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_OCP_QP_H_ -#define HPIPM_S_OCP_QP_H_ - - - -#include -#include - -#include "hpipm_s_ocp_qp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_ocp_qp - { - struct s_ocp_qp_dim *dim; - struct blasfeo_smat *BAbt; // dynamics matrix & vector work space - struct blasfeo_smat *RSQrq; // hessian of cost & vector work space - struct blasfeo_smat *DCt; // inequality constraints matrix - struct blasfeo_svec *b; // dynamics vector - struct blasfeo_svec *rqz; // gradient of cost & gradient of slacks - struct blasfeo_svec *d; // inequality constraints vector - struct blasfeo_svec *d_mask; // inequality constraints mask vector - struct blasfeo_svec *m; // rhs of complementarity condition - struct blasfeo_svec *Z; // (diagonal) hessian of slacks - int **idxb; // indices of box constrained variables within [u; x] - int **idxs_rev; // index of soft constraints (reverse storage) - int **idxe; // indices of constraints within [bu, bx, g] that are equalities, subset of [0, ..., nbu+nbx+ng-1] - int *diag_H_flag; // flag the fact that Hessian is diagonal - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t s_ocp_qp_strsize(); -// -hpipm_size_t s_ocp_qp_memsize(struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_create(struct s_ocp_qp_dim *dim, struct s_ocp_qp *qp, void *memory); -// -void s_ocp_qp_copy_all(struct s_ocp_qp *qp_orig, struct s_ocp_qp *qp_dest); - -// setters -// -void s_ocp_qp_set_all_zero(struct s_ocp_qp *qp); -// -void s_ocp_qp_set_rhs_zero(struct s_ocp_qp *qp); -// -void s_ocp_qp_set_all(float **A, float **B, float **b, float **Q, float **S, float **R, float **q, float **r, int **idxbx, float **lbx, float **ubx, int **idxbu, float **lbu, float **ubu, float **C, float **D, float **lg, float **ug, float **Zl, float **Zu, float **zl, float **zu, int **idxs, float **ls, float **us, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_all_rowmaj(float **A, float **B, float **b, float **Q, float **S, float **R, float **q, float **r, int **idxbx, float **lbx, float **ubx, int **idxbu, float **lbu, float **ubu, float **C, float **D, float **lg, float **ug, float **Zl, float **Zu, float **zl, float **zu, int **idxs, float **ls, float **us, struct s_ocp_qp *qp); -// -void s_ocp_qp_set(char *fiels_name, int stage, void *value, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_el(char *fiels_name, int stage, int index, void *value, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_A(int stage, float *mat, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_B(int stage, float *mat, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_b(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_Q(int stage, float *mat, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_S(int stage, float *mat, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_R(int stage, float *mat, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_q(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_r(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_lb(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_lb_mask(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_ub(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_ub_mask(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_lbx(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_lbx_mask(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_el_lbx(int stage, int index, float *elem, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_ubx(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_ubx_mask(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_el_ubx(int stage, int index, float *elem, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_lbu(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_lbu_mask(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_ubu(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_ubu_mask(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_idxb(int stage, int *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_idxbx(int stage, int *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_Jbx(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_idxbu(int stage, int *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_Jbu(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_C(int stage, float *mat, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_D(int stage, float *mat, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_lg(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_lg_mask(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_ug(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_ug_mask(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_Zl(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_Zu(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_zl(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_zu(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_lls(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_lls_mask(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_lus(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_lus_mask(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_idxs(int stage, int *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_idxs_rev(int stage, int *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_Jsbu(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_Jsbx(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_Jsg(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_idxe(int stage, int *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_idxbxe(int stage, int *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_idxbue(int stage, int *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_idxge(int stage, int *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_Jbxe(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_Jbue(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_Jge(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_diag_H_flag(int stage, int *value, struct s_ocp_qp *qp); - -// getters -// -void s_ocp_qp_get(char *field, int stage, struct s_ocp_qp *qp, void *value); -// -void s_ocp_qp_get_A(int stage, struct s_ocp_qp *qp, float *mat); -// -void s_ocp_qp_get_B(int stage, struct s_ocp_qp *qp, float *mat); -// -void s_ocp_qp_get_b(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_Q(int stage, struct s_ocp_qp *qp, float *mat); -// -void s_ocp_qp_get_S(int stage, struct s_ocp_qp *qp, float *mat); -// -void s_ocp_qp_get_R(int stage, struct s_ocp_qp *qp, float *mat); -// -void s_ocp_qp_get_q(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_r(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_ub(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_ub_mask(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_lb(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_lb_mask(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_lbx(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_lbx_mask(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_ubx(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_ubx_mask(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_lbu(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_lbu_mask(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_ubu(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_ubu_mask(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_idxb(int stage, struct s_ocp_qp *qp, int *vec); -// -//void s_ocp_qp_get_idxbx(int stage, struct s_ocp_qp *qp, int *vec); -// -//void s_ocp_qp_get_Jbx(int stage, struct s_ocp_qp *qp, float *vec); -// -//void s_ocp_qp_get_idxbu(int stage, struct s_ocp_qp *qp, int *vec); -// -//void s_ocp_qp_get_Jbu(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_C(int stage, struct s_ocp_qp *qp, float *mat); -// -void s_ocp_qp_get_D(int stage, struct s_ocp_qp *qp, float *mat); -// -void s_ocp_qp_get_lg(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_lg_mask(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_ug(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_ug_mask(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_Zl(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_Zu(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_zl(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_zu(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_lls(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_lls_mask(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_lus(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_lus_mask(int stage, struct s_ocp_qp *qp, float *vec); -// XXX only valid if there is one slack per softed constraint !!! -void s_ocp_qp_get_idxs(int stage, struct s_ocp_qp *qp, int *vec); -// -void s_ocp_qp_get_idxs_rev(int stage, struct s_ocp_qp *qp, int *vec); -// -//void s_ocp_qp_get_Jsbu(int stage, struct s_ocp_qp *qp, float *vec); -// -//void s_ocp_qp_get_Jsbx(int stage, struct s_ocp_qp *qp, float *vec); -// -//void s_ocp_qp_get_Jsg(int stage, struct s_ocp_qp *qp, float *vec); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_OCP_QP_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_dim.h b/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_dim.h deleted file mode 100644 index bce80243b3..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_dim.h +++ /dev/null @@ -1,141 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_OCP_QP_DIM_H_ -#define HPIPM_S_OCP_QP_DIM_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_ocp_qp_dim - { - int *nx; // number of states - int *nu; // number of inputs - int *nb; // number of box constraints - int *nbx; // number of state box constraints - int *nbu; // number of input box constraints - int *ng; // number of general constraints - int *ns; // number of soft constraints - int *nsbx; // number of soft state box constraints - int *nsbu; // number of soft input box constraints - int *nsg; // number of soft general constraints - int *nbxe; // number of state box constraints which are equality - int *nbue; // number of input box constraints which are equality - int *nge; // number of general constraints which are equality - int N; // horizon length - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_ocp_qp_dim_strsize(); -// -hpipm_size_t s_ocp_qp_dim_memsize(int N); -// -void s_ocp_qp_dim_create(int N, struct s_ocp_qp_dim *qp_dim, void *memory); -// -void s_ocp_qp_dim_copy_all(struct s_ocp_qp_dim *dim_orig, struct s_ocp_qp_dim *dim_dest); -// -void s_ocp_qp_dim_set_all(int *nx, int *nu, int *nbx, int *nbu, int *ng, int *nsbx, int *nsbu, int *nsg, struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_dim_set(char *field, int stage, int value, struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_dim_set_nx(int stage, int value, struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_dim_set_nu(int stage, int value, struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_dim_set_nbx(int stage, int value, struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_dim_set_nbu(int stage, int value, struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_dim_set_ng(int stage, int value, struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_dim_set_ns(int stage, int value, struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_dim_set_nsbx(int stage, int value, struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_dim_set_nsbu(int stage, int value, struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_dim_set_nsg(int stage, int value, struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_dim_set_nbxe(int stage, int value, struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_dim_set_nbue(int stage, int value, struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_dim_set_nge(int stage, int value, struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_dim_get(struct s_ocp_qp_dim *dim, char *field, int stage, int *value); -// -void s_ocp_qp_dim_get_N(struct s_ocp_qp_dim *dim, int *value); -// -void s_ocp_qp_dim_get_nx(struct s_ocp_qp_dim *dim, int stage, int *value); -// -void s_ocp_qp_dim_get_nu(struct s_ocp_qp_dim *dim, int stage, int *value); -// -void s_ocp_qp_dim_get_nbx(struct s_ocp_qp_dim *dim, int stage, int *value); -// -void s_ocp_qp_dim_get_nbu(struct s_ocp_qp_dim *dim, int stage, int *value); -// -void s_ocp_qp_dim_get_ng(struct s_ocp_qp_dim *dim, int stage, int *value); -// -void s_ocp_qp_dim_get_ns(struct s_ocp_qp_dim *dim, int stage, int *value); -// -void s_ocp_qp_dim_get_nsbx(struct s_ocp_qp_dim *dim, int stage, int *value); -// -void s_ocp_qp_dim_get_nsbu(struct s_ocp_qp_dim *dim, int stage, int *value); -// -void s_ocp_qp_dim_get_nsg(struct s_ocp_qp_dim *dim, int stage, int *value); -// -void s_ocp_qp_dim_get_nbxe(struct s_ocp_qp_dim *dim, int stage, int *value); -// -void s_ocp_qp_dim_get_nbue(struct s_ocp_qp_dim *dim, int stage, int *value); -// -void s_ocp_qp_dim_get_nge(struct s_ocp_qp_dim *dim, int stage, int *value); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_S_OCP_QP_DIM_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_ipm.h b/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_ipm.h deleted file mode 100644 index 11f3c47be6..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_ipm.h +++ /dev/null @@ -1,250 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_OCP_QP_IPM_H_ -#define HPIPM_S_OCP_QP_IPM_H_ - - - -#include -#include - -#include -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_ocp_qp_ipm_arg - { - float mu0; // initial value for complementarity slackness - float alpha_min; // exit cond on step length - float res_g_max; // exit cond on inf norm of residuals - float res_b_max; // exit cond on inf norm of residuals - float res_d_max; // exit cond on inf norm of residuals - float res_m_max; // exit cond on inf norm of residuals - float reg_prim; // reg of primal hessian - float lam_min; // min value in lam vector - float t_min; // min value in t vector - float tau_min; // min value of barrier parameter - int iter_max; // exit cond in iter number - int stat_max; // iterations saved in stat - int pred_corr; // use Mehrotra's predictor-corrector IPM algirthm - int cond_pred_corr; // conditional Mehrotra's predictor-corrector - int itref_pred_max; // max number of iterative refinement steps for predictor step - int itref_corr_max; // max number of iterative refinement steps for corrector step - int warm_start; // 0 no warm start, 1 warm start primal sol, 2 warm start primal and dual sol - int square_root_alg; // 0 classical Riccati, 1 square-root Riccati - int lq_fact; // 0 syrk+potrf, 1 mix, 2 lq (for square_root_alg==1) - int abs_form; // absolute IPM formulation - int comp_dual_sol_eq; // dual solution of equality constraints (only for abs_form==1) - int comp_res_exit; // compute residuals on exit (only for abs_form==1 and comp_dual_sol_eq==1) - int comp_res_pred; // compute residuals of prediction - int split_step; // use different steps for primal and dual variables - int var_init_scheme; // variables initialization scheme - int t_lam_min; // clip t and lam: 0 no, 1 in Gamma computation, 2 in solution - int mode; - hpipm_size_t memsize; - }; - - - -struct s_ocp_qp_ipm_ws - { - struct s_core_qp_ipm_workspace *core_workspace; - struct s_ocp_qp_res_ws *res_workspace; - struct s_ocp_qp_dim *dim; // cache dim - struct s_ocp_qp_sol *sol_step; - struct s_ocp_qp_sol *sol_itref; - struct s_ocp_qp *qp_step; - struct s_ocp_qp *qp_itref; - struct s_ocp_qp_res *res; - struct s_ocp_qp_res *res_itref; - struct blasfeo_svec *Gamma; // hessian update - struct blasfeo_svec *gamma; // hessian update - struct blasfeo_svec *tmp_nuxM; // work space of size nxM - struct blasfeo_svec *tmp_nbgM; // work space of size nbM+ngM - struct blasfeo_svec *tmp_nsM; // work space of size nsM - struct blasfeo_svec *Pb; // Pb - struct blasfeo_svec *Zs_inv; - struct blasfeo_svec *tmp_m; - struct blasfeo_svec *l; // cache linear part for _get_ric_xxx - struct blasfeo_smat *L; - struct blasfeo_smat *Ls; - struct blasfeo_smat *P; - struct blasfeo_smat *Lh; - struct blasfeo_smat *AL; - struct blasfeo_smat *lq0; - struct blasfeo_smat *tmp_nxM_nxM; - float *stat; // convergence statistics - int *use_hess_fact; - void *lq_work0; - float qp_res[4]; // infinity norm of residuals - int iter; // iteration number - int stat_max; // iterations saved in stat - int stat_m; // number of recorded stat per IPM iter - int use_Pb; - int status; // solver status - int square_root_alg; // cache from arg - int lq_fact; // cache from arg - int mask_constr; // use constr mask - int valid_ric_vec; // meaningful riccati vectors - int valid_ric_p; // form of riccati p: 0 p*inv(L), 1 p - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_ocp_qp_ipm_arg_strsize(); -// -hpipm_size_t s_ocp_qp_ipm_arg_memsize(struct s_ocp_qp_dim *ocp_dim); -// -void s_ocp_qp_ipm_arg_create(struct s_ocp_qp_dim *ocp_dim, struct s_ocp_qp_ipm_arg *arg, void *mem); -// -void s_ocp_qp_ipm_arg_set_default(enum hpipm_mode mode, struct s_ocp_qp_ipm_arg *arg); -// -void s_ocp_qp_ipm_arg_set(char *field, void *value, struct s_ocp_qp_ipm_arg *arg); -// set maximum number of iterations -void s_ocp_qp_ipm_arg_set_iter_max(int *iter_max, struct s_ocp_qp_ipm_arg *arg); -// set minimum step lenght -void s_ocp_qp_ipm_arg_set_alpha_min(float *alpha_min, struct s_ocp_qp_ipm_arg *arg); -// set initial value of barrier parameter -void s_ocp_qp_ipm_arg_set_mu0(float *mu0, struct s_ocp_qp_ipm_arg *arg); -// set exit tolerance on stationarity condition -void s_ocp_qp_ipm_arg_set_tol_stat(float *tol_stat, struct s_ocp_qp_ipm_arg *arg); -// set exit tolerance on equality constr -void s_ocp_qp_ipm_arg_set_tol_eq(float *tol_eq, struct s_ocp_qp_ipm_arg *arg); -// set exit tolerance on inequality constr -void s_ocp_qp_ipm_arg_set_tol_ineq(float *tol_ineq, struct s_ocp_qp_ipm_arg *arg); -// set exit tolerance on complementarity condition -void s_ocp_qp_ipm_arg_set_tol_comp(float *tol_comp, struct s_ocp_qp_ipm_arg *arg); -// set regularization of primal variables -void s_ocp_qp_ipm_arg_set_reg_prim(float *tol_comp, struct s_ocp_qp_ipm_arg *arg); -// set warm start: 0 no warm start, 1 primal var -void s_ocp_qp_ipm_arg_set_warm_start(int *warm_start, struct s_ocp_qp_ipm_arg *arg); -// Mehrotra's predictor-corrector IPM algorithm: 0 no predictor-corrector, 1 use predictor-corrector -void s_ocp_qp_ipm_arg_set_pred_corr(int *pred_corr, struct s_ocp_qp_ipm_arg *arg); -// conditional predictor-corrector: 0 no conditinal predictor-corrector, 1 conditional predictor-corrector -void s_ocp_qp_ipm_arg_set_cond_pred_corr(int *value, struct s_ocp_qp_ipm_arg *arg); -// set riccati algorithm: 0 classic, 1 square-root -void s_ocp_qp_ipm_arg_set_ric_alg(int *alg, struct s_ocp_qp_ipm_arg *arg); -// dual solution of equality constraints (only for abs_form==1) -void s_ocp_qp_ipm_arg_set_comp_dual_sol_eq(int *value, struct s_ocp_qp_ipm_arg *arg); -// compute residuals after solution -void s_ocp_qp_ipm_arg_set_comp_res_exit(int *value, struct s_ocp_qp_ipm_arg *arg); -// compute residuals of prediction -void s_ocp_qp_ipm_arg_set_comp_res_pred(int *alg, struct s_ocp_qp_ipm_arg *arg); -// min value of lam in the solution -void s_ocp_qp_ipm_arg_set_lam_min(float *value, struct s_ocp_qp_ipm_arg *arg); -// min value of t in the solution -void s_ocp_qp_ipm_arg_set_t_min(float *value, struct s_ocp_qp_ipm_arg *arg); -// min value of tau in the solution -void s_ocp_qp_ipm_arg_set_tau_min(float *value, struct s_ocp_qp_ipm_arg *arg); -// set split step: 0 same step, 1 different step for primal and dual variables -void s_ocp_qp_ipm_arg_set_split_step(int *value, struct s_ocp_qp_ipm_arg *arg); -// variables initialization scheme -void s_ocp_qp_ipm_arg_set_var_init_scheme(int *value, struct s_ocp_qp_ipm_arg *arg); -// clip t and lam: 0 no, 1 in Gamma computation, 2 in solution -void s_ocp_qp_ipm_arg_set_t_lam_min(int *value, struct s_ocp_qp_ipm_arg *arg); - -// -hpipm_size_t s_ocp_qp_ipm_ws_strsize(); -// -hpipm_size_t s_ocp_qp_ipm_ws_memsize(struct s_ocp_qp_dim *ocp_dim, struct s_ocp_qp_ipm_arg *arg); -// -void s_ocp_qp_ipm_ws_create(struct s_ocp_qp_dim *ocp_dim, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws, void *mem); -// -void s_ocp_qp_ipm_get(char *field, struct s_ocp_qp_ipm_ws *ws, void *value); -// -void s_ocp_qp_ipm_get_status(struct s_ocp_qp_ipm_ws *ws, int *status); -// -void s_ocp_qp_ipm_get_iter(struct s_ocp_qp_ipm_ws *ws, int *iter); -// -void s_ocp_qp_ipm_get_max_res_stat(struct s_ocp_qp_ipm_ws *ws, float *res_stat); -// -void s_ocp_qp_ipm_get_max_res_eq(struct s_ocp_qp_ipm_ws *ws, float *res_eq); -// -void s_ocp_qp_ipm_get_max_res_ineq(struct s_ocp_qp_ipm_ws *ws, float *res_ineq); -// -void s_ocp_qp_ipm_get_max_res_comp(struct s_ocp_qp_ipm_ws *ws, float *res_comp); -// -void s_ocp_qp_ipm_get_stat(struct s_ocp_qp_ipm_ws *ws, float **stat); -// -void s_ocp_qp_ipm_get_stat_m(struct s_ocp_qp_ipm_ws *ws, int *stat_m); -// -void s_ocp_qp_ipm_get_ric_Lr(struct s_ocp_qp *qp, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws, int stage, float *Lr); -// -void s_ocp_qp_ipm_get_ric_Ls(struct s_ocp_qp *qp, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws, int stage, float *Ls); -// -void s_ocp_qp_ipm_get_ric_P(struct s_ocp_qp *qp, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws, int stage, float *P); -// -void s_ocp_qp_ipm_get_ric_lr(struct s_ocp_qp *qp, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws, int stage, float *lr); -// -void s_ocp_qp_ipm_get_ric_p(struct s_ocp_qp *qp, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws, int stage, float *p); -// feedback control gain in the form u = K x + k -void s_ocp_qp_ipm_get_ric_K(struct s_ocp_qp *qp, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws, int stage, float *K); -// feedback control gain in the form u = K x + k -void s_ocp_qp_ipm_get_ric_k(struct s_ocp_qp *qp, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws, int stage, float *k); -// -void s_ocp_qp_init_var(struct s_ocp_qp *qp, struct s_ocp_qp_sol *qp_sol, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws); -// -void s_ocp_qp_ipm_abs_step(int kk, struct s_ocp_qp *qp, struct s_ocp_qp_sol *qp_sol, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws); -// -void s_ocp_qp_ipm_delta_step(int kk, struct s_ocp_qp *qp, struct s_ocp_qp_sol *qp_sol, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws); -// -void s_ocp_qp_ipm_solve(struct s_ocp_qp *qp, struct s_ocp_qp_sol *qp_sol, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws); -// -void s_ocp_qp_ipm_predict(struct s_ocp_qp *qp, struct s_ocp_qp_sol *qp_sol, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws); -// -void s_ocp_qp_ipm_sens(struct s_ocp_qp *qp, struct s_ocp_qp_sol *qp_sol, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_OCP_QP_IPM_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_kkt.h b/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_kkt.h deleted file mode 100644 index 3eb1f4aae8..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_kkt.h +++ /dev/null @@ -1,66 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - -#ifndef HPIPM_S_OCP_QP_KKT_H_ -#define HPIPM_S_OCP_QP_KKT_H_ - -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - -// -void s_ocp_qp_fact_solve_kkt_unconstr(struct s_ocp_qp *qp, struct s_ocp_qp_sol *qp_sol, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws); -// -void s_ocp_qp_fact_solve_kkt_step(struct s_ocp_qp *qp, struct s_ocp_qp_sol *qp_sol, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws); -// -void s_ocp_qp_fact_lq_solve_kkt_step(struct s_ocp_qp *qp, struct s_ocp_qp_sol *qp_sol, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws); -// -void s_ocp_qp_solve_kkt_step(struct s_ocp_qp *qp, struct s_ocp_qp_sol *qp_sol, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - -#endif // HPIPM_S_OCP_QP_KKT_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_red.h b/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_red.h deleted file mode 100644 index 5a7b3b0703..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_red.h +++ /dev/null @@ -1,118 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_OCP_QP_RED_H_ -#define HPIPM_S_OCP_QP_RED_H_ - - - -#include -#include - -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_ocp_qp_reduce_eq_dof_arg - { - float lam_min; - float t_min; - int alias_unchanged; // do not keep copy unchanged stage - int comp_prim_sol; // primal solution (v) - int comp_dual_sol_eq; // dual solution equality constr (pi) - int comp_dual_sol_ineq; // dual solution inequality constr (lam t) - hpipm_size_t memsize; // memory size in bytes - }; - - - -struct s_ocp_qp_reduce_eq_dof_ws - { - struct blasfeo_svec *tmp_nuxM; - struct blasfeo_svec *tmp_nbgM; - int *e_imask_ux; - int *e_imask_d; - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -void s_ocp_qp_dim_reduce_eq_dof(struct s_ocp_qp_dim *dim, struct s_ocp_qp_dim *dim_red); -// -hpipm_size_t s_ocp_qp_reduce_eq_dof_arg_memsize(); -// -void s_ocp_qp_reduce_eq_dof_arg_create(struct s_ocp_qp_reduce_eq_dof_arg *arg, void *mem); -// -void s_ocp_qp_reduce_eq_dof_arg_set_default(struct s_ocp_qp_reduce_eq_dof_arg *arg); -// -void s_ocp_qp_reduce_eq_dof_arg_set_alias_unchanged(struct s_ocp_qp_reduce_eq_dof_arg *arg, int value); -// -void s_ocp_qp_reduce_eq_dof_arg_set_comp_prim_sol(struct s_ocp_qp_reduce_eq_dof_arg *arg, int value); -// -void s_ocp_qp_reduce_eq_dof_arg_set_comp_dual_sol_eq(struct s_ocp_qp_reduce_eq_dof_arg *arg, int value); -// -void s_ocp_qp_reduce_eq_dof_arg_set_comp_dual_sol_ineq(struct s_ocp_qp_reduce_eq_dof_arg *arg, int value); -// -hpipm_size_t s_ocp_qp_reduce_eq_dof_ws_memsize(struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_reduce_eq_dof_ws_create(struct s_ocp_qp_dim *dim, struct s_ocp_qp_reduce_eq_dof_ws *work, void *mem); -// -void s_ocp_qp_reduce_eq_dof(struct s_ocp_qp *qp, struct s_ocp_qp *qp_red, struct s_ocp_qp_reduce_eq_dof_arg *arg, struct s_ocp_qp_reduce_eq_dof_ws *work); -// -void s_ocp_qp_reduce_eq_dof_lhs(struct s_ocp_qp *qp, struct s_ocp_qp *qp_red, struct s_ocp_qp_reduce_eq_dof_arg *arg, struct s_ocp_qp_reduce_eq_dof_ws *work); -// -void s_ocp_qp_reduce_eq_dof_rhs(struct s_ocp_qp *qp, struct s_ocp_qp *qp_red, struct s_ocp_qp_reduce_eq_dof_arg *arg, struct s_ocp_qp_reduce_eq_dof_ws *work); -// -void s_ocp_qp_restore_eq_dof(struct s_ocp_qp *qp, struct s_ocp_qp_sol *qp_sol_red, struct s_ocp_qp_sol *qp_sol, struct s_ocp_qp_reduce_eq_dof_arg *arg, struct s_ocp_qp_reduce_eq_dof_ws *work); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_S_OCP_QP_RED_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_res.h b/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_res.h deleted file mode 100644 index 821585da65..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_res.h +++ /dev/null @@ -1,114 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_OCP_QP_RES_H_ -#define HPIPM_S_OCP_QP_RES_H_ - - - -#include -#include - -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_ocp_qp_res - { - struct s_ocp_qp_dim *dim; - struct blasfeo_svec *res_g; // q-residuals - struct blasfeo_svec *res_b; // b-residuals - struct blasfeo_svec *res_d; // d-residuals - struct blasfeo_svec *res_m; // m-residuals - float res_max[4]; // max of residuals - float res_mu; // mu-residual - hpipm_size_t memsize; - }; - - - -struct s_ocp_qp_res_ws - { - struct blasfeo_svec *tmp_nbgM; // work space of size nbM+ngM - struct blasfeo_svec *tmp_nsM; // work space of size nsM - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_ocp_qp_res_memsize(struct s_ocp_qp_dim *ocp_dim); -// -void s_ocp_qp_res_create(struct s_ocp_qp_dim *ocp_dim, struct s_ocp_qp_res *res, void *mem); -// -hpipm_size_t s_ocp_qp_res_ws_memsize(struct s_ocp_qp_dim *ocp_dim); -// -void s_ocp_qp_res_ws_create(struct s_ocp_qp_dim *ocp_dim, struct s_ocp_qp_res_ws *workspace, void *mem); -// -void s_ocp_qp_res_compute(struct s_ocp_qp *qp, struct s_ocp_qp_sol *qp_sol, struct s_ocp_qp_res *res, struct s_ocp_qp_res_ws *ws); -// -void s_ocp_qp_res_compute_lin(struct s_ocp_qp *qp, struct s_ocp_qp_sol *qp_sol, struct s_ocp_qp_sol *qp_step, struct s_ocp_qp_res *res, struct s_ocp_qp_res_ws *ws); -// -void s_ocp_qp_res_compute_inf_norm(struct s_ocp_qp_res *res); -// -void s_ocp_qp_res_get_all(struct s_ocp_qp_res *res, float **res_r, float **res_q, float **res_ls, float **res_us, float **res_b, float **res_d_lb, float **res_d_ub, float **res_d_lg, float **res_d_ug, float **res_d_ls, float **res_d_us, float **res_m_lb, float **res_m_ub, float **res_m_lg, float **res_m_ug, float **res_m_ls, float **res_m_us); -// -void s_ocp_qp_res_get_max_res_stat(struct s_ocp_qp_res *res, float *value); -// -void s_ocp_qp_res_get_max_res_eq(struct s_ocp_qp_res *res, float *value); -// -void s_ocp_qp_res_get_max_res_ineq(struct s_ocp_qp_res *res, float *value); -// -void s_ocp_qp_res_get_max_res_comp(struct s_ocp_qp_res *res, float *value); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_S_OCP_QP_RES_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_sol.h b/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_sol.h deleted file mode 100644 index 94dfa0d003..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_sol.h +++ /dev/null @@ -1,128 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_OCP_QP_SOL_H_ -#define HPIPM_S_OCP_QP_SOL_H_ - - - -#include -#include - -#include "hpipm_s_ocp_qp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_ocp_qp_sol - { - struct s_ocp_qp_dim *dim; - struct blasfeo_svec *ux; - struct blasfeo_svec *pi; - struct blasfeo_svec *lam; - struct blasfeo_svec *t; - void *misc; - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t s_ocp_qp_sol_strsize(); -// -hpipm_size_t s_ocp_qp_sol_memsize(struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_sol_create(struct s_ocp_qp_dim *dim, struct s_ocp_qp_sol *qp_sol, void *memory); -// -void s_ocp_qp_sol_copy_all(struct s_ocp_qp_sol *qp_sol_orig, struct s_ocp_qp_sol *qp_sol_dest); -// -void s_qp_sol_get_all(struct s_ocp_qp_sol *qp_sol, float **u, float **x, float **ls, float **us, float **pi, float **lam_lb, float **lam_ub, float **lam_lg, float **lam_ug, float **lam_ls, float **lam_us); -// -void s_qp_sol_get_all_rowmaj(struct s_ocp_qp_sol *qp_sol, float **u, float **x, float **ls, float **us, float **pi, float **lam_lb, float **lam_ub, float **lam_lg, float **lam_ug, float **lam_ls, float **lam_us); -// -void s_ocp_qp_sol_set_all(float **u, float **x, float **ls, float **us, float **pi, float **lam_lb, float **lam_ub, float **lam_lg, float **lam_ug, float **lam_ls, float **lam_us, struct s_ocp_qp_sol *qp_sol); -// -void s_ocp_qp_sol_get(char *field, int stage, struct s_ocp_qp_sol *qp_sol, float *vec); -// -void s_ocp_qp_sol_get_u(int stage, struct s_ocp_qp_sol *qp_sol, float *vec); -// -void s_ocp_qp_sol_get_x(int stage, struct s_ocp_qp_sol *qp_sol, float *vec); -// -void s_ocp_qp_sol_get_sl(int stage, struct s_ocp_qp_sol *qp_sol, float *vec); -// -void s_ocp_qp_sol_get_su(int stage, struct s_ocp_qp_sol *qp_sol, float *vec); -// -void s_ocp_qp_sol_get_pi(int stage, struct s_ocp_qp_sol *qp_sol, float *vec); -// -void s_ocp_qp_sol_get_lam_lb(int stage, struct s_ocp_qp_sol *qp_sol, float *vec); -// -void s_ocp_qp_sol_get_lam_lbu(int stage, struct s_ocp_qp_sol *qp_sol, float *vec); -// -void s_ocp_qp_sol_get_lam_lbx(int stage, struct s_ocp_qp_sol *qp_sol, float *vec); -// -void s_ocp_qp_sol_get_lam_ub(int stage, struct s_ocp_qp_sol *qp_sol, float *vec); -// -void s_ocp_qp_sol_get_lam_ubu(int stage, struct s_ocp_qp_sol *qp_sol, float *vec); -// -void s_ocp_qp_sol_get_lam_ubx(int stage, struct s_ocp_qp_sol *qp_sol, float *vec); -// -void s_ocp_qp_sol_get_lam_lg(int stage, struct s_ocp_qp_sol *qp_sol, float *vec); -// -void s_ocp_qp_sol_get_lam_ug(int stage, struct s_ocp_qp_sol *qp_sol, float *vec); -// -void s_ocp_qp_sol_set(char *field, int stage, float *vec, struct s_ocp_qp_sol *qp_sol); -// -void s_ocp_qp_sol_set_u(int stage, float *vec, struct s_ocp_qp_sol *qp_sol); -// -void s_ocp_qp_sol_set_x(int stage, float *vec, struct s_ocp_qp_sol *qp_sol); -// -void s_ocp_qp_sol_set_sl(int stage, float *vec, struct s_ocp_qp_sol *qp_sol); -// -void s_ocp_qp_sol_set_su(int stage, float *vec, struct s_ocp_qp_sol *qp_sol); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_OCP_QP_SOL_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_utils.h b/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_utils.h deleted file mode 100644 index a4f832a5ea..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_utils.h +++ /dev/null @@ -1,83 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_OCP_QP_UTILS_H_ -#define HPIPM_S_OCP_QP_UTILS_H_ - - - -#include -#include - -#include "hpipm_s_ocp_qp_dim.h" -#include "hpipm_s_ocp_qp.h" -#include "hpipm_s_ocp_qp_sol.h" -#include "hpipm_s_ocp_qp_ipm.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void s_ocp_qp_dim_print(struct s_ocp_qp_dim *qp_dim); -// -void s_ocp_qp_dim_codegen(char *file_name, char *mode, struct s_ocp_qp_dim *qp_dim); -// -void s_ocp_qp_print(struct s_ocp_qp_dim *qp_dim, struct s_ocp_qp *qp); -// -void s_ocp_qp_codegen(char *file_name, char *mode, struct s_ocp_qp_dim *qp_dim, struct s_ocp_qp *qp); -// -void s_ocp_qp_sol_print(struct s_ocp_qp_dim *qp_dim, struct s_ocp_qp_sol *ocp_qp_sol); -// -void s_ocp_qp_ipm_arg_print(struct s_ocp_qp_dim *qp_dim, struct s_ocp_qp_ipm_arg *arg); -// -void s_ocp_qp_ipm_arg_codegen(char *file_name, char *mode, struct s_ocp_qp_dim *qp_dim, struct s_ocp_qp_ipm_arg *arg); -// -void s_ocp_qp_res_print(struct s_ocp_qp_dim *qp_dim, struct s_ocp_qp_res *ocp_qp_res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_OCP_QP_UTILS_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_part_cond.h b/third_party/acados/include/hpipm/include/hpipm_s_part_cond.h deleted file mode 100644 index e40511e69f..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_part_cond.h +++ /dev/null @@ -1,115 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_S_PART_COND_H_ -#define HPIPM_S_PART_COND_H_ - - - -#include -#include - -#include "hpipm_s_cond.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_part_cond_qp_arg - { - struct s_cond_qp_arg *cond_arg; - int N2; - hpipm_size_t memsize; - }; - - - -struct s_part_cond_qp_ws - { - struct s_cond_qp_ws *cond_workspace; - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_part_cond_qp_arg_memsize(int N2); -// -void s_part_cond_qp_arg_create(int N2, struct s_part_cond_qp_arg *cond_arg, void *mem); -// -void s_part_cond_qp_arg_set_default(struct s_part_cond_qp_arg *cond_arg); -// set riccati-like algorithm: 0 classical, 1 squre-root -void s_part_cond_qp_arg_set_ric_alg(int ric_alg, struct s_part_cond_qp_arg *cond_arg); -// -void s_part_cond_qp_arg_set_comp_prim_sol(int value, struct s_part_cond_qp_arg *cond_arg); -// -void s_part_cond_qp_arg_set_comp_dual_sol_eq(int value, struct s_part_cond_qp_arg *cond_arg); -// -void s_part_cond_qp_arg_set_comp_dual_sol_ineq(int value, struct s_part_cond_qp_arg *cond_arg); - -// -void s_part_cond_qp_compute_block_size(int N, int N2, int *block_size); -// -void s_part_cond_qp_compute_dim(struct s_ocp_qp_dim *ocp_dim, int *block_size, struct s_ocp_qp_dim *part_dense_dim); -// -hpipm_size_t s_part_cond_qp_ws_memsize(struct s_ocp_qp_dim *ocp_dim, int *block_size, struct s_ocp_qp_dim *part_dense_dim, struct s_part_cond_qp_arg *cond_arg); -// -void s_part_cond_qp_ws_create(struct s_ocp_qp_dim *ocp_dim, int *block_size, struct s_ocp_qp_dim *part_dense_dim, struct s_part_cond_qp_arg *cond_arg, struct s_part_cond_qp_ws *cond_ws, void *mem); -// -void s_part_cond_qp_cond(struct s_ocp_qp *ocp_qp, struct s_ocp_qp *part_dense_qp, struct s_part_cond_qp_arg *cond_arg, struct s_part_cond_qp_ws *cond_ws); -// -void s_part_cond_qp_cond_lhs(struct s_ocp_qp *ocp_qp, struct s_ocp_qp *part_dense_qp, struct s_part_cond_qp_arg *cond_arg, struct s_part_cond_qp_ws *cond_ws); -// -void s_part_cond_qp_cond_rhs(struct s_ocp_qp *ocp_qp, struct s_ocp_qp *part_dense_qp, struct s_part_cond_qp_arg *cond_arg, struct s_part_cond_qp_ws *cond_ws); -// -void s_part_cond_qp_expand_sol(struct s_ocp_qp *ocp_qp, struct s_ocp_qp *part_dense_qp, struct s_ocp_qp_sol *part_dense_qp_sol, struct s_ocp_qp_sol *ocp_qp_sol, struct s_part_cond_qp_arg *cond_arg, struct s_part_cond_qp_ws *cond_ws); - -// -void s_part_cond_qp_update(int *idxc, struct s_ocp_qp *ocp_qp, struct s_ocp_qp *part_dense_qp, struct s_part_cond_qp_arg *cond_arg, struct s_part_cond_qp_ws *cond_ws); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_PART_COND_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_part_cond_qcqp.h b/third_party/acados/include/hpipm/include/hpipm_s_part_cond_qcqp.h deleted file mode 100644 index 311f7000bf..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_part_cond_qcqp.h +++ /dev/null @@ -1,107 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_S_PART_COND_QCQP_H_ -#define HPIPM_S_PART_COND_QCQP_H_ - - - -#include -#include - -#include "hpipm_s_cond_qcqp.h" - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_part_cond_qcqp_arg - { - struct s_cond_qcqp_arg *cond_arg; - int N2; - hpipm_size_t memsize; - }; - - - -struct s_part_cond_qcqp_ws - { - struct s_cond_qcqp_ws *cond_ws; - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_part_cond_qcqp_arg_memsize(int N2); -// -void s_part_cond_qcqp_arg_create(int N2, struct s_part_cond_qcqp_arg *cond_arg, void *mem); -// -void s_part_cond_qcqp_arg_set_default(struct s_part_cond_qcqp_arg *cond_arg); -// set riccati-like algorithm: 0 classical, 1 squre-root -void s_part_cond_qcqp_arg_set_ric_alg(int ric_alg, struct s_part_cond_qcqp_arg *cond_arg); - -// -void s_part_cond_qcqp_compute_block_size(int N, int N2, int *block_size); -// -void s_part_cond_qcqp_compute_dim(struct s_ocp_qcqp_dim *ocp_dim, int *block_size, struct s_ocp_qcqp_dim *part_dense_dim); -// -hpipm_size_t s_part_cond_qcqp_ws_memsize(struct s_ocp_qcqp_dim *ocp_dim, int *block_size, struct s_ocp_qcqp_dim *part_dense_dim, struct s_part_cond_qcqp_arg *cond_arg); -// -void s_part_cond_qcqp_ws_create(struct s_ocp_qcqp_dim *ocp_dim, int *block_size, struct s_ocp_qcqp_dim *part_dense_dim, struct s_part_cond_qcqp_arg *cond_arg, struct s_part_cond_qcqp_ws *cond_ws, void *mem); -// -void s_part_cond_qcqp_cond(struct s_ocp_qcqp *ocp_qp, struct s_ocp_qcqp *part_dense_qp, struct s_part_cond_qcqp_arg *cond_arg, struct s_part_cond_qcqp_ws *cond_ws); -// -void s_part_cond_qcqp_cond_lhs(struct s_ocp_qcqp *ocp_qp, struct s_ocp_qcqp *part_dense_qp, struct s_part_cond_qcqp_arg *cond_arg, struct s_part_cond_qcqp_ws *cond_ws); -// -void s_part_cond_qcqp_cond_rhs(struct s_ocp_qcqp *ocp_qp, struct s_ocp_qcqp *part_dense_qp, struct s_part_cond_qcqp_arg *cond_arg, struct s_part_cond_qcqp_ws *cond_ws); -// -void s_part_cond_qcqp_expand_sol(struct s_ocp_qcqp *ocp_qp, struct s_ocp_qcqp *part_dense_qp, struct s_ocp_qcqp_sol *part_dense_qp_sol, struct s_ocp_qcqp_sol *ocp_qp_sol, struct s_part_cond_qcqp_arg *cond_arg, struct s_part_cond_qcqp_ws *cond_ws); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_PART_COND_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_sim_erk.h b/third_party/acados/include/hpipm/include/hpipm_s_sim_erk.h deleted file mode 100644 index 1a05ad1a28..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_sim_erk.h +++ /dev/null @@ -1,121 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_SIM_ERK_H_ -#define HPIPM_S_SIM_ERK_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -struct s_sim_erk_arg - { - struct s_sim_rk_data *rk_data; // integrator data - float h; // step size - int steps; // number of steps -// int for_sens; // compute adjoint sensitivities -// int adj_sens; // compute adjoint sensitivities - hpipm_size_t memsize; - }; - - - -struct s_sim_erk_ws - { - void (*ode)(int t, float *x, float *p, void *ode_args, float *xdot); // function pointer to ode - void (*vde_for)(int t, float *x, float *p, void *ode_args, float *xdot); // function pointer to forward vde - void (*vde_adj)(int t, float *adj_in, void *ode_args, float *adj_out); // function pointer to adjoint vde - void *ode_args; // pointer to ode args - struct s_sim_erk_arg *erk_arg; // erk arg - float *K; // internal variables - float *x_for; // states and forward sensitivities - float *x_traj; // states at all steps - float *l; // adjoint sensitivities - float *p; // parameter - float *x_tmp; // temporary states and forward sensitivities - float *adj_in; - float *adj_tmp; - int nx; // number of states - int np; // number of parameters - int nf; // number of forward sensitivities - int na; // number of adjoint sensitivities - int nf_max; // max number of forward sensitivities - int na_max; // max number of adjoint sensitivities - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_sim_erk_arg_memsize(); -// -void s_sim_erk_arg_create(struct s_sim_erk_arg *erk_arg, void *mem); -// -void s_sim_erk_arg_set_all(struct s_sim_rk_data *rk_data, float h, int steps, struct s_sim_erk_arg *erk_arg); - -// -hpipm_size_t s_sim_erk_ws_memsize(struct s_sim_erk_arg *erk_arg, int nx, int np, int nf_max, int na_max); -// -void s_sim_erk_ws_create(struct s_sim_erk_arg *erk_arg, int nx, int np, int nf_max, int na_max, struct s_sim_erk_ws *work, void *memory); -// -void s_sim_erk_ws_set_all(int nf, int na, float *x, float *fs, float *bs, float *p, void (*ode)(int t, float *x, float *p, void *ode_args, float *xdot), void (*vde_for)(int t, float *x, float *p, void *ode_args, float *xdot), void (*vde_adj)(int t, float *adj_in, void *ode_args, float *adj_out), void *ode_args, struct s_sim_erk_ws *work); -// number of directions for forward sensitivities -void s_sim_erk_ws_set_nf(int *nf, struct s_sim_erk_ws *work); -// parameters (e.g. inputs) -void s_sim_erk_ws_set_p(float *p, struct s_sim_erk_ws *work); -// state -void s_sim_erk_ws_set_x(float *x, struct s_sim_erk_ws *work); -// forward sensitivities -void s_sim_erk_ws_set_fs(float *fs, struct s_sim_erk_ws *work); -// ode funtion -void s_sim_erk_ws_set_ode(void (*ode)(int t, float *x, float *p, void *ode_args, float *xdot), struct s_sim_erk_ws *work); -// forward vde function -void s_sim_erk_ws_set_vde_for(void (*ode)(int t, float *x, float *p, void *ode_args, float *xdot), struct s_sim_erk_ws *work); -// ode_args, passed straight to the ode/vde_for/vde_adj functions -void s_sim_erk_ws_set_ode_args(void *ode_args, struct s_sim_erk_ws *work); -// state -void s_sim_erk_ws_get_x(struct s_sim_erk_ws *work, float *x); -// forward sensitivities -void s_sim_erk_ws_get_fs(struct s_sim_erk_ws *work, float *fs); -// -void s_sim_erk_solve(struct s_sim_erk_arg *arg, struct s_sim_erk_ws *work); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // HPIPM_D_SIM_ERK_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_sim_rk.h b/third_party/acados/include/hpipm/include/hpipm_s_sim_rk.h deleted file mode 100644 index 53acd71498..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_sim_rk.h +++ /dev/null @@ -1,72 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_SIM_RK_H_ -#define HPIPM_S_SIM_RK_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - -struct s_sim_rk_data - { - float *A_rk; // A in butcher tableau - float *B_rk; // b in butcher tableau - float *C_rk; // c in butcher tableau - int expl; // erk vs irk - int ns; // number of stages - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_sim_rk_data_memsize(int ns); -// -void s_sim_rk_data_create(int ns, struct s_sim_rk_data *rk_data, void *memory); -// -void s_sim_rk_data_init_default(char *field, struct s_sim_rk_data *rk_data); -// -void s_sim_rk_data_set_all(int expl, float *A_rk, float *B_rk, float *C_rk, struct s_sim_rk_data *rk_data); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // HPIPM_S_SIM_RK_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp.h b/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp.h deleted file mode 100644 index 450e992624..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp.h +++ /dev/null @@ -1,213 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_TREE_OCP_QCQP_H_ -#define HPIPM_S_TREE_OCP_QCQP_H_ - - - -#include -#include - -#include "hpipm_s_tree_ocp_qcqp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_tree_ocp_qcqp - { - struct s_tree_ocp_qcqp_dim *dim; - struct blasfeo_smat *BAbt; // Nn-1 - struct blasfeo_smat *RSQrq; // Nn - struct blasfeo_smat *DCt; // Nn - struct blasfeo_smat **Hq; // Nn - struct blasfeo_svec *b; // Nn-1 - struct blasfeo_svec *rqz; // Nn - struct blasfeo_svec *d; // Nn - struct blasfeo_svec *d_mask; // Nn - struct blasfeo_svec *m; // Nn - struct blasfeo_svec *Z; // Nn - int **idxb; // indices of box constrained variables within [u; x] // Nn - int **idxs_rev; // index of soft constraints - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t s_tree_ocp_qcqp_memsize(struct s_tree_ocp_qcqp_dim *dim); -// -void s_tree_ocp_qcqp_create(struct s_tree_ocp_qcqp_dim *dim, struct s_tree_ocp_qcqp *qp, void *memory); -// -void s_tree_ocp_qcqp_set_all(float **A, float **B, float **b, float **Q, float **S, float **R, float **q, float **r, int **idxb, float **d_lb, float **d_ub, float **C, float **D, float **d_lg, float **d_ug, float **Zl, float **Zu, float **zl, float **zu, int **idxs, float **d_ls, float **d_us, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set(char *field_name, int node_edge, void *value, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_A(int edge, float *mat, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_B(int edge, float *mat, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_b(int edge, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_Q(int node, float *mat, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_S(int node, float *mat, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_R(int node, float *mat, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_q(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_r(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_lb(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_lb_mask(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_ub(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_ub_mask(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_lbx(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_lbx_mask(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_ubx(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_ubx_mask(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_lbu(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_lbu_mask(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_ubu(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_ubu_mask(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_idxb(int node, int *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_idxbx(int node, int *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_Jbx(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_idxbu(int node, int *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_Jbu(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_C(int node, float *mat, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_D(int node, float *mat, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_lg(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_lg_mask(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_ug(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_ug_mask(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_Qq(int node, float *mat, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_Sq(int node, float *mat, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_Rq(int node, float *mat, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_qq(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_rq(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_uq(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_uq_mask(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_Zl(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_Zu(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_zl(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_zu(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_lls(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_lls_mask(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_lus(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_lus_mask(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_idxs(int node, int *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_idxs_rev(int node, int *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_Jsbu(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_Jsbx(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_Jsg(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_Jsq(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -//void s_tree_ocp_qcqp_set_idxe(int node, int *vec, struct s_tree_ocp_qcqp *qp); -// -//void s_tree_ocp_qcqp_set_idxbxe(int node, int *vec, struct s_tree_ocp_qcqp *qp); -// -//void s_tree_ocp_qcqp_set_idxbue(int node, int *vec, struct s_tree_ocp_qcqp *qp); -// -//void s_tree_ocp_qcqp_set_idxge(int node, int *vec, struct s_tree_ocp_qcqp *qp); -// -//void s_tree_ocp_qcqp_set_Jbxe(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -//void s_tree_ocp_qcqp_set_Jbue(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -//void s_tree_ocp_qcqp_set_Jge(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -//void s_tree_ocp_qcqp_set_diag_H_flag(int node, int *value, struct s_tree_ocp_qcqp *qp); - - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_TREE_OCP_QCQP_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_dim.h b/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_dim.h deleted file mode 100644 index 7a49d51995..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_dim.h +++ /dev/null @@ -1,118 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_TREE_OCP_QCQP_DIM_H_ -#define HPIPM_S_TREE_OCP_QCQP_DIM_H_ - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_tree_ocp_qcqp_dim - { - struct s_tree_ocp_qp_dim *qp_dim; // dim of qp approximation - struct tree *ttree; // tree describing node conndection - int *nx; // number of states // Nn - int *nu; // number of inputs // Nn - int *nb; // number of box constraints // Nn - int *nbx; // number of state box constraints // Nn - int *nbu; // number of input box constraints // Nn - int *ng; // number of general constraints // Nn - int *nq; // number of (upper) quadratic constraints - int *ns; // number of soft constraints // Nn - int *nsbx; // number of soft state box constraints - int *nsbu; // number of soft input box constraints - int *nsg; // number of soft general constraints - int *nsq; // number of (upper) soft quadratic constraints - int Nn; // number of nodes - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_tree_ocp_qcqp_dim_strsize(); -// -hpipm_size_t s_tree_ocp_qcqp_dim_memsize(int Nn); -// -void s_tree_ocp_qcqp_dim_create(int Nn, struct s_tree_ocp_qcqp_dim *qp_dim, void *memory); -// -void s_tree_ocp_qcqp_dim_set_tree(struct tree *ttree, struct s_tree_ocp_qcqp_dim *dim); -// -void s_tree_ocp_qcqp_dim_set(char *field, int stage, int value, struct s_tree_ocp_qcqp_dim *dim); -// -void s_tree_ocp_qcqp_dim_set_nx(int stage, int value, struct s_tree_ocp_qcqp_dim *dim); -// -void s_tree_ocp_qcqp_dim_set_nu(int stage, int value, struct s_tree_ocp_qcqp_dim *dim); -// -void s_tree_ocp_qcqp_dim_set_nbx(int stage, int value, struct s_tree_ocp_qcqp_dim *dim); -// -void s_tree_ocp_qcqp_dim_set_nbu(int stage, int value, struct s_tree_ocp_qcqp_dim *dim); -// -void s_tree_ocp_qcqp_dim_set_ng(int stage, int value, struct s_tree_ocp_qcqp_dim *dim); -// -void s_tree_ocp_qcqp_dim_set_nq(int stage, int value, struct s_tree_ocp_qcqp_dim *dim); -// -void s_tree_ocp_qcqp_dim_set_ns(int stage, int value, struct s_tree_ocp_qcqp_dim *dim); -// -void s_tree_ocp_qcqp_dim_set_nsbx(int stage, int value, struct s_tree_ocp_qcqp_dim *dim); -// -void s_tree_ocp_qcqp_dim_set_nsbu(int stage, int value, struct s_tree_ocp_qcqp_dim *dim); -// -void s_tree_ocp_qcqp_dim_set_nsg(int stage, int value, struct s_tree_ocp_qcqp_dim *dim); -// -void s_tree_ocp_qcqp_dim_set_nsq(int stage, int value, struct s_tree_ocp_qcqp_dim *dim); -// -//void s_tree_ocp_qcqp_dim_set_nbxe(int stage, int value, struct s_tree_ocp_qcqp_dim *dim); -// -//void s_tree_ocp_qcqp_dim_set_nbue(int stage, int value, struct s_tree_ocp_qcqp_dim *dim); -// -//void s_tree_ocp_qcqp_dim_set_nge(int stage, int value, struct s_tree_ocp_qcqp_dim *dim); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_S_TREE_OCP_QCQP_DIM_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_ipm.h b/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_ipm.h deleted file mode 100644 index 69d65914c5..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_ipm.h +++ /dev/null @@ -1,192 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_TREE_OCP_QCQP_IPM_H_ -#define HPIPM_S_TREE_OCP_QCQP_IPM_H_ - - - -#include -#include - -#include -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_tree_ocp_qcqp_ipm_arg - { - struct s_tree_ocp_qp_ipm_arg *qp_arg; - float mu0; // initial value for complementarity slackness - float alpha_min; // exit cond on step length - float res_g_max; // exit cond on inf norm of residuals - float res_b_max; // exit cond on inf norm of residuals - float res_d_max; // exit cond on inf norm of residuals - float res_m_max; // exit cond on inf norm of residuals - float reg_prim; // reg of primal hessian - float lam_min; // min value in lam vector - float t_min; // min value in t vector - int iter_max; // exit cond in iter number - int stat_max; // iterations saved in stat - int pred_corr; // use Mehrotra's predictor-corrector IPM algirthm - int cond_pred_corr; // conditional Mehrotra's predictor-corrector - int itref_pred_max; // max number of iterative refinement steps for predictor step - int itref_corr_max; // max number of iterative refinement steps for corrector step - int warm_start; // 0 no warm start, 1 warm start primal sol, 2 warm start primal and dual sol -// int square_root_alg; // 0 classical Riccati, 1 square-root Riccati - int lq_fact; // 0 syrk+potrf, 1 mix, 2 lq (for square_root_alg==1) - int abs_form; // absolute IPM formulation - int comp_dual_sol_eq; // dual solution of equality constraints (only for abs_form==1) - int comp_res_exit; // compute residuals on exit (only for abs_form==1 and comp_dual_sol_eq==1) -// int comp_res_pred; // compute residuals of prediction - int split_step; // use different step for primal and dual variables - int t_lam_min; // clip t and lam: 0 no, 1 in Gamma computation, 2 in solution - int mode; - hpipm_size_t memsize; - }; - - - -struct s_tree_ocp_qcqp_ipm_ws - { - struct s_tree_ocp_qp_ipm_ws *qp_ws; - struct s_tree_ocp_qp *qp; - struct s_tree_ocp_qp_sol *qp_sol; - struct s_tree_ocp_qcqp_res_ws *qcqp_res_ws; - struct s_tree_ocp_qcqp_res *qcqp_res; - struct blasfeo_svec *tmp_nuxM; - int iter; // iteration number - int status; - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_tree_ocp_qcqp_ipm_arg_strsize(); -// -hpipm_size_t s_tree_ocp_qcqp_ipm_arg_memsize(struct s_tree_ocp_qcqp_dim *ocp_dim); -// -void s_tree_ocp_qcqp_ipm_arg_create(struct s_tree_ocp_qcqp_dim *ocp_dim, struct s_tree_ocp_qcqp_ipm_arg *arg, void *mem); -// -void s_tree_ocp_qcqp_ipm_arg_set_default(enum hpipm_mode mode, struct s_tree_ocp_qcqp_ipm_arg *arg); -// -void s_tree_ocp_qcqp_ipm_arg_set(char *field, void *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// set maximum number of iterations -void s_tree_ocp_qcqp_ipm_arg_set_iter_max(int *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// set minimum step lenght -void s_tree_ocp_qcqp_ipm_arg_set_alpha_min(float *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// set initial value of barrier parameter -void s_tree_ocp_qcqp_ipm_arg_set_mu0(float *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on stationarity condition -void s_tree_ocp_qcqp_ipm_arg_set_tol_stat(float *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on equality constr -void s_tree_ocp_qcqp_ipm_arg_set_tol_eq(float *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on inequality constr -void s_tree_ocp_qcqp_ipm_arg_set_tol_ineq(float *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on complementarity condition -void s_tree_ocp_qcqp_ipm_arg_set_tol_comp(float *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// set regularization of primal variables -void s_tree_ocp_qcqp_ipm_arg_set_reg_prim(float *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// set warm start: 0 no warm start, 1 primal var -void s_tree_ocp_qcqp_ipm_arg_set_warm_start(int *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// Mehrotra's predictor-corrector IPM algorithm: 0 no predictor-corrector, 1 use predictor-corrector -void s_tree_ocp_qcqp_ipm_arg_set_pred_corr(int *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// conditional predictor-corrector: 0 no conditinal predictor-corrector, 1 conditional predictor-corrector -void s_tree_ocp_qcqp_ipm_arg_set_cond_pred_corr(int *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// set riccati algorithm: 0 classic, 1 square-root -//void s_tree_ocp_qcqp_ipm_arg_set_ric_alg(int *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// compute residuals after solution -void s_tree_ocp_qcqp_ipm_arg_set_comp_res_exit(int *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// compute residuals of prediction -//void s_tree_ocp_qcqp_ipm_arg_set_comp_res_pred(int *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// min value of lam in the solution -void s_tree_ocp_qcqp_ipm_arg_set_lam_min(float *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// min value of t in the solution -void s_tree_ocp_qcqp_ipm_arg_set_t_min(float *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// use different step for primal and dual variables -void s_tree_ocp_qcqp_ipm_arg_set_split_step(int *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// clip t and lam: 0 no, 1 in Gamma computation, 2 in solution -void s_tree_ocp_qcqp_ipm_arg_set_t_lam_min(int *value, struct s_tree_ocp_qcqp_ipm_arg *arg); - -// -hpipm_size_t s_tree_ocp_qcqp_ipm_ws_strsize(); -// -hpipm_size_t s_tree_ocp_qcqp_ipm_ws_memsize(struct s_tree_ocp_qcqp_dim *ocp_dim, struct s_tree_ocp_qcqp_ipm_arg *arg); -// -void s_tree_ocp_qcqp_ipm_ws_create(struct s_tree_ocp_qcqp_dim *ocp_dim, struct s_tree_ocp_qcqp_ipm_arg *arg, struct s_tree_ocp_qcqp_ipm_ws *ws, void *mem); -// -void s_tree_ocp_qcqp_ipm_get(char *field, struct s_tree_ocp_qcqp_ipm_ws *ws, void *value); -// -void s_tree_ocp_qcqp_ipm_get_status(struct s_tree_ocp_qcqp_ipm_ws *ws, int *status); -// -void s_tree_ocp_qcqp_ipm_get_iter(struct s_tree_ocp_qcqp_ipm_ws *ws, int *iter); -// -void s_tree_ocp_qcqp_ipm_get_max_res_stat(struct s_tree_ocp_qcqp_ipm_ws *ws, float *res_stat); -// -void s_tree_ocp_qcqp_ipm_get_max_res_eq(struct s_tree_ocp_qcqp_ipm_ws *ws, float *res_eq); -// -void s_tree_ocp_qcqp_ipm_get_max_res_ineq(struct s_tree_ocp_qcqp_ipm_ws *ws, float *res_ineq); -// -void s_tree_ocp_qcqp_ipm_get_max_res_comp(struct s_tree_ocp_qcqp_ipm_ws *ws, float *res_comp); -// -void s_tree_ocp_qcqp_ipm_get_stat(struct s_tree_ocp_qcqp_ipm_ws *ws, float **stat); -// -void s_tree_ocp_qcqp_ipm_get_stat_m(struct s_tree_ocp_qcqp_ipm_ws *ws, int *stat_m); -// -void s_tree_ocp_qcqp_init_var(struct s_tree_ocp_qcqp *qp, struct s_tree_ocp_qcqp_sol *qp_sol, struct s_tree_ocp_qcqp_ipm_arg *arg, struct s_tree_ocp_qcqp_ipm_ws *ws); -// -void s_tree_ocp_qcqp_ipm_solve(struct s_tree_ocp_qcqp *qp, struct s_tree_ocp_qcqp_sol *qp_sol, struct s_tree_ocp_qcqp_ipm_arg *arg, struct s_tree_ocp_qcqp_ipm_ws *ws); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_S_TREE_OCP_QCQP_IPM_H_ - - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_res.h b/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_res.h deleted file mode 100644 index d0d84a6f23..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_res.h +++ /dev/null @@ -1,109 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_TREE_OCP_QCQP_RES_H_ -#define HPIPM_S_TREE_OCP_QCQP_RES_H_ - - - -#include -#include - -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_tree_ocp_qcqp_res - { - struct s_tree_ocp_qcqp_dim *dim; - struct blasfeo_svec *res_g; // q-residuals - struct blasfeo_svec *res_b; // b-residuals - struct blasfeo_svec *res_d; // d-residuals - struct blasfeo_svec *res_m; // m-residuals - float res_max[4]; // max of residuals - float res_mu; // mu-residual - hpipm_size_t memsize; - }; - - - -struct s_tree_ocp_qcqp_res_ws - { - struct blasfeo_svec *tmp_nuxM; // work space of size nuM+nxM - struct blasfeo_svec *tmp_nbgqM; // work space of size nbM+ngM+nqM - struct blasfeo_svec *tmp_nsM; // work space of size nsM - struct blasfeo_svec *q_fun; // value for evaluation of quadr constr - struct blasfeo_svec *q_adj; // value for adjoint of quadr constr - int use_q_fun; // reuse cached value for evaluation of quadr constr - int use_q_adj; // reuse cached value for adjoint of quadr constr - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_tree_ocp_qcqp_res_memsize(struct s_tree_ocp_qcqp_dim *ocp_dim); -// -void s_tree_ocp_qcqp_res_create(struct s_tree_ocp_qcqp_dim *ocp_dim, struct s_tree_ocp_qcqp_res *res, void *mem); -// -hpipm_size_t s_tree_ocp_qcqp_res_ws_memsize(struct s_tree_ocp_qcqp_dim *ocp_dim); -// -void s_tree_ocp_qcqp_res_ws_create(struct s_tree_ocp_qcqp_dim *ocp_dim, struct s_tree_ocp_qcqp_res_ws *ws, void *mem); -// -void s_tree_ocp_qcqp_res_compute(struct s_tree_ocp_qcqp *qp, struct s_tree_ocp_qcqp_sol *qp_sol, struct s_tree_ocp_qcqp_res *res, struct s_tree_ocp_qcqp_res_ws *ws); -// -void s_tree_ocp_qcqp_res_compute_inf_norm(struct s_tree_ocp_qcqp_res *res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_S_TREE_OCP_QCQP_RES_H_ - - - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_sol.h b/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_sol.h deleted file mode 100644 index 47f038c6b3..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_sol.h +++ /dev/null @@ -1,97 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_TREE_OCP_QCQP_SOL_H_ -#define HPIPM_S_TREE_OCP_QCQP_SOL_H_ - - - -#include -#include - -#include "hpipm_s_tree_ocp_qcqp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - -struct s_tree_ocp_qcqp_sol - { - struct s_tree_ocp_qcqp_dim *dim; - struct blasfeo_svec *ux; - struct blasfeo_svec *pi; - struct blasfeo_svec *lam; - struct blasfeo_svec *t; - void *misc; - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t s_tree_ocp_qcqp_sol_memsize(struct s_tree_ocp_qcqp_dim *dim); -// -void s_tree_ocp_qcqp_sol_create(struct s_tree_ocp_qcqp_dim *dim, struct s_tree_ocp_qcqp_sol *qp_sol, void *memory); -// -void s_tree_ocp_qcqp_sol_get_u(int node, struct s_tree_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qcqp_sol_get_x(int node, struct s_tree_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qcqp_sol_get_sl(int node, struct s_tree_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qcqp_sol_get_su(int node, struct s_tree_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qcqp_sol_get_pi(int edge, struct s_tree_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qcqp_sol_get_lam_lb(int node, struct s_tree_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qcqp_sol_get_lam_ub(int node, struct s_tree_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qcqp_sol_get_lam_lg(int node, struct s_tree_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qcqp_sol_get_lam_ug(int node, struct s_tree_ocp_qcqp_sol *qp_sol, float *vec); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_TREE_OCP_QCQP_SOL_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_utils.h b/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_utils.h deleted file mode 100644 index 79528de1ce..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_utils.h +++ /dev/null @@ -1,85 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_TREE_OCP_QCQP_UTILS_H_ -#define HPIPM_S_TREE_OCP_QCQP_UTILS_H_ - - - -#include -#include - -#include "hpipm_s_tree_ocp_qcqp_dim.h" -#include "hpipm_s_tree_ocp_qcqp.h" -#include "hpipm_s_tree_ocp_qcqp_sol.h" -#include "hpipm_s_tree_ocp_qcqp_ipm.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void s_tree_ocp_qcqp_dim_print(struct s_tree_ocp_qcqp_dim *qp_dim); -// -//void s_tree_ocp_qcqp_dim_codegen(char *file_name, char *mode, struct s_tree_ocp_qcqp_dim *qp_dim); -// -void s_tree_ocp_qcqp_print(struct s_tree_ocp_qcqp_dim *qp_dim, struct s_tree_ocp_qcqp *qp); -// -//void s_tree_ocp_qcqp_codegen(char *file_name, char *mode, struct s_tree_ocp_qcqp_dim *qp_dim, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_sol_print(struct s_tree_ocp_qcqp_dim *qp_dim, struct s_tree_ocp_qcqp_sol *ocp_qcqp_sol); -// -void s_tree_ocp_qcqp_ipm_arg_print(struct s_tree_ocp_qcqp_dim *qp_dim, struct s_tree_ocp_qcqp_ipm_arg *arg); -// -//void s_tree_ocp_qcqp_ipm_arg_codegen(char *file_name, char *mode, struct s_tree_ocp_qcqp_dim *qp_dim, struct s_tree_ocp_qcqp_ipm_arg *arg); -// -void s_tree_ocp_qcqp_res_print(struct s_tree_ocp_qcqp_dim *qp_dim, struct s_tree_ocp_qcqp_res *ocp_qcqp_res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_S_TREE_OCP_QCQP_UTILS_H_ - - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp.h b/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp.h deleted file mode 100644 index 722b930b9a..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp.h +++ /dev/null @@ -1,196 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_TREE_OCP_QP_H_ -#define HPIPM_S_TREE_OCP_QP_H_ - - - -#include -#include - -#include "hpipm_s_tree_ocp_qp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_tree_ocp_qp - { - struct s_tree_ocp_qp_dim *dim; - struct blasfeo_smat *BAbt; // Nn-1 - struct blasfeo_smat *RSQrq; // Nn - struct blasfeo_smat *DCt; // Nn - struct blasfeo_svec *b; // Nn-1 - struct blasfeo_svec *rqz; // Nn - struct blasfeo_svec *d; // Nn - struct blasfeo_svec *d_mask; // Nn - struct blasfeo_svec *m; // Nn - struct blasfeo_svec *Z; // Nn - int **idxb; // indices of box constrained variables within [u; x] // Nn -// int **idxs; // index of soft constraints - int **idxs_rev; // index of soft constraints - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t s_tree_ocp_qp_memsize(struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_create(struct s_tree_ocp_qp_dim *dim, struct s_tree_ocp_qp *qp, void *memory); -// -void s_tree_ocp_qp_set_all(float **A, float **B, float **b, float **Q, float **S, float **R, float **q, float **r, int **idxb, float **d_lb, float **d_ub, float **C, float **D, float **d_lg, float **d_ug, float **Zl, float **Zu, float **zl, float **zu, int **idxs, float **d_ls, float **d_us, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set(char *field_name, int node_edge, void *value, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_A(int edge, float *mat, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_B(int edge, float *mat, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_b(int edge, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_Q(int node, float *mat, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_S(int node, float *mat, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_R(int node, float *mat, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_q(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_r(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_lb(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_lb_mask(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_ub(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_ub_mask(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_lbx(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_lbx_mask(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_ubx(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_ubx_mask(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_lbu(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_lbu_mask(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_ubu(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_ubu_mask(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_idxb(int node, int *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_idxbx(int node, int *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_Jbx(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_idxbu(int node, int *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_Jbu(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_C(int node, float *mat, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_D(int node, float *mat, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_lg(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_lg_mask(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_ug(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_ug_mask(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_Zl(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_Zu(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_zl(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_zu(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_lls(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_lls_mask(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_lus(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_lus_mask(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_idxs(int node, int *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_idxs_rev(int node, int *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_Jsbu(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_Jsbx(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_Jsg(int node, float *vec, struct s_tree_ocp_qp *qp); -// -//void s_tree_ocp_qp_set_idxe(int node, int *vec, struct s_tree_ocp_qp *qp); -// -//void s_tree_ocp_qp_set_idxbxe(int node, int *vec, struct s_tree_ocp_qp *qp); -// -//void s_tree_ocp_qp_set_idxbue(int node, int *vec, struct s_tree_ocp_qp *qp); -// -//void s_tree_ocp_qp_set_idxge(int node, int *vec, struct s_tree_ocp_qp *qp); -// -//void s_tree_ocp_qp_set_Jbxe(int node, float *vec, struct s_tree_ocp_qp *qp); -// -//void s_tree_ocp_qp_set_Jbue(int node, float *vec, struct s_tree_ocp_qp *qp); -// -//void s_tree_ocp_qp_set_Jge(int node, float *vec, struct s_tree_ocp_qp *qp); -// -//void s_tree_ocp_qp_set_diag_H_flag(int node, int *value, struct s_tree_ocp_qp *qp); - - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_TREE_OCP_QP_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_dim.h b/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_dim.h deleted file mode 100644 index 90df57182b..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_dim.h +++ /dev/null @@ -1,111 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_TREE_OCP_QP_DIM_H_ -#define HPIPM_S_TREE_OCP_QP_DIM_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_tree_ocp_qp_dim - { - struct tree *ttree; // tree describing node conndection - int *nx; // number of states // Nn - int *nu; // number of inputs // Nn - int *nb; // number of box constraints // Nn - int *nbx; // number of state box constraints // Nn - int *nbu; // number of input box constraints // Nn - int *ng; // number of general constraints // Nn - int *ns; // number of soft constraints // Nn - int *nsbx; // number of soft state box constraints - int *nsbu; // number of soft input box constraints - int *nsg; // number of soft general constraints - int Nn; // number of nodes - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_tree_ocp_qp_dim_strsize(); -// -hpipm_size_t s_tree_ocp_qp_dim_memsize(int Nn); -// -void s_tree_ocp_qp_dim_create(int Nn, struct s_tree_ocp_qp_dim *qp_dim, void *memory); -// -void s_tree_ocp_qp_dim_set_all(struct tree *ttree, int *nx, int *nu, int *nbx, int *nbu, int *ng, int *nsbx, int *nsbu, int *nsg, struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_dim_set_tree(struct tree *ttree, struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_dim_set(char *field, int stage, int value, struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_dim_set_nx(int stage, int value, struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_dim_set_nu(int stage, int value, struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_dim_set_nbx(int stage, int value, struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_dim_set_nbu(int stage, int value, struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_dim_set_ng(int stage, int value, struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_dim_set_ns(int stage, int value, struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_dim_set_nsbx(int stage, int value, struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_dim_set_nsbu(int stage, int value, struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_dim_set_nsg(int stage, int value, struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_dim_set_nbxe(int stage, int value, struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_dim_set_nbue(int stage, int value, struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_dim_set_nge(int stage, int value, struct s_tree_ocp_qp_dim *dim); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_S_TREE_OCP_QP_DIM_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_ipm.h b/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_ipm.h deleted file mode 100644 index f8c26d3173..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_ipm.h +++ /dev/null @@ -1,208 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_S_TREE_OCP_QP_IPM_H_ -#define HPIPM_S_TREE_OCP_QP_IPM_H_ - - - -#include -#include - -#include -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_tree_ocp_qp_ipm_arg - { - float mu0; // initial value for duality measure - float alpha_min; // exit cond on step length - float res_g_max; // exit cond on inf norm of residuals - float res_b_max; // exit cond on inf norm of residuals - float res_d_max; // exit cond on inf norm of residuals - float res_m_max; // exit cond on inf norm of residuals - float reg_prim; // reg of primal hessian - float lam_min; // min value in lam vector - float t_min; // min value in t vector - float tau_min; // min value of barrier parameter - int iter_max; // exit cond in iter number - int stat_max; // iterations saved in stat - int stat_m; // number of recorded stat per IPM iter - int pred_corr; // use Mehrotra's predictor-corrector IPM algirthm - int cond_pred_corr; // conditional Mehrotra's predictor-corrector - int itref_pred_max; // max number of iterative refinement steps for predictor step - int itref_corr_max; // max number of iterative refinement steps for corrector step - int warm_start; // 0 no warm start, 1 warm start primal sol, 2 warm start primal and dual sol - int lq_fact; // 0 syrk+potrf, 1 mix, 2 lq - int abs_form; // absolute IPM formulation - int comp_dual_sol_eq; // dual solution (only for abs_form==1) - int comp_res_exit; // compute residuals on exit (only for abs_form==1 and comp_dual_sol==1) - int split_step; // use different steps for primal and dual variables - int t_lam_min; // clip t and lam: 0 no, 1 in Gamma computation, 2 in solution - int mode; - hpipm_size_t memsize; - }; - - - -struct s_tree_ocp_qp_ipm_ws - { - struct s_core_qp_ipm_workspace *core_workspace; - struct s_tree_ocp_qp_res_ws *res_workspace; - struct s_tree_ocp_qp_sol *sol_step; - struct s_tree_ocp_qp_sol *sol_itref; - struct s_tree_ocp_qp *qp_step; - struct s_tree_ocp_qp *qp_itref; - struct s_tree_ocp_qp_res *res_itref; - struct s_tree_ocp_qp_res *res; - struct blasfeo_svec *Gamma; // hessian update - struct blasfeo_svec *gamma; // hessian update - struct blasfeo_svec *tmp_nxM; // work space of size nxM - struct blasfeo_svec *tmp_nbgM; // work space of size nbgM - struct blasfeo_svec *tmp_nsM; // work space of size nsM - struct blasfeo_svec *Pb; // Pb - struct blasfeo_svec *Zs_inv; - struct blasfeo_smat *L; - struct blasfeo_smat *Lh; - struct blasfeo_smat *AL; - struct blasfeo_smat *lq0; - struct blasfeo_svec *tmp_m; - float *stat; // convergence statistics - int *use_hess_fact; - void *lq_work0; - float qp_res[4]; // infinity norm of residuals - int iter; // iteration number - int stat_max; // iterations saved in stat - int stat_m; // number of recorded stat per IPM iter - int use_Pb; - int status; // solver status - int lq_fact; // cache from arg - int mask_constr; // use constr mask - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_tree_ocp_qp_ipm_arg_memsize(struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_ipm_arg_create(struct s_tree_ocp_qp_dim *dim, struct s_tree_ocp_qp_ipm_arg *arg, void *mem); -// -void s_tree_ocp_qp_ipm_arg_set_default(enum hpipm_mode mode, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_iter_max(int *iter_max, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_alpha_min(float *alpha_min, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_mu0(float *mu0, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_tol_stat(float *tol_stat, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_tol_eq(float *tol_eq, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_tol_ineq(float *tol_ineq, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_tol_comp(float *tol_comp, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_reg_prim(float *reg, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_warm_start(int *warm_start, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_pred_corr(int *pred_corr, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_cond_pred_corr(int *value, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_comp_dual_sol_eq(int *value, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_comp_res_exit(int *value, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_lam_min(float *value, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_t_min(float *value, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_tau_min(float *value, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_split_step(int *value, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_t_lam_min(int *value, struct s_tree_ocp_qp_ipm_arg *arg); - -// -hpipm_size_t s_tree_ocp_qp_ipm_ws_memsize(struct s_tree_ocp_qp_dim *dim, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_ws_create(struct s_tree_ocp_qp_dim *dim, struct s_tree_ocp_qp_ipm_arg *arg, struct s_tree_ocp_qp_ipm_ws *ws, void *mem); -// -void s_tree_ocp_qp_ipm_get_status(struct s_tree_ocp_qp_ipm_ws *ws, int *status); -// -void s_tree_ocp_qp_ipm_get_iter(struct s_tree_ocp_qp_ipm_ws *ws, int *iter); -// -void s_tree_ocp_qp_ipm_get_max_res_stat(struct s_tree_ocp_qp_ipm_ws *ws, float *res_stat); -// -void s_tree_ocp_qp_ipm_get_max_res_eq(struct s_tree_ocp_qp_ipm_ws *ws, float *res_eq); -// -void s_tree_ocp_qp_ipm_get_max_res_ineq(struct s_tree_ocp_qp_ipm_ws *ws, float *res_ineq); -// -void s_tree_ocp_qp_ipm_get_max_res_comp(struct s_tree_ocp_qp_ipm_ws *ws, float *res_comp); -// -void s_tree_ocp_qp_ipm_get_stat(struct s_tree_ocp_qp_ipm_ws *ws, float **stat); -// -void s_tree_ocp_qp_ipm_get_stat_m(struct s_tree_ocp_qp_ipm_ws *ws, int *stat_m); -// -void s_tree_ocp_qp_init_var(struct s_tree_ocp_qp *qp, struct s_tree_ocp_qp_sol *qp_sol, struct s_tree_ocp_qp_ipm_arg *arg, struct s_tree_ocp_qp_ipm_ws *ws); -// -void s_tree_ocp_qp_ipm_abs_step(int kk, struct s_tree_ocp_qp *qp, struct s_tree_ocp_qp_sol *qp_sol, struct s_tree_ocp_qp_ipm_arg *arg, struct s_tree_ocp_qp_ipm_ws *ws); -// -void s_tree_ocp_qp_ipm_delta_step(int kk, struct s_tree_ocp_qp *qp, struct s_tree_ocp_qp_sol *qp_sol, struct s_tree_ocp_qp_ipm_arg *arg, struct s_tree_ocp_qp_ipm_ws *ws); -// -void s_tree_ocp_qp_ipm_solve(struct s_tree_ocp_qp *qp, struct s_tree_ocp_qp_sol *qp_sol, struct s_tree_ocp_qp_ipm_arg *arg, struct s_tree_ocp_qp_ipm_ws *ws); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_TREE_OCP_QP_IPM_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_kkt.h b/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_kkt.h deleted file mode 100644 index bcf7354783..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_kkt.h +++ /dev/null @@ -1,54 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - -#ifdef __cplusplus -extern "C" { -#endif - -// -void s_tree_ocp_qp_fact_solve_kkt_unconstr(struct s_tree_ocp_qp *qp, struct s_tree_ocp_qp_sol *qp_sol, struct s_tree_ocp_qp_ipm_arg *arg, struct s_tree_ocp_qp_ipm_ws *ws); -// -void s_tree_ocp_qp_fact_solve_kkt_step(struct s_tree_ocp_qp *qp, struct s_tree_ocp_qp_sol *qp_sol, struct s_tree_ocp_qp_ipm_arg *arg, struct s_tree_ocp_qp_ipm_ws *ws); -// -void s_tree_ocp_qp_fact_lq_solve_kkt_step(struct s_tree_ocp_qp *qp, struct s_tree_ocp_qp_sol *qp_sol, struct s_tree_ocp_qp_ipm_arg *arg, struct s_tree_ocp_qp_ipm_ws *ws); -// -void s_tree_ocp_qp_solve_kkt_step(struct s_tree_ocp_qp *qp, struct s_tree_ocp_qp_sol *qp_sol, struct s_tree_ocp_qp_ipm_arg *arg, struct s_tree_ocp_qp_ipm_ws *ws); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_res.h b/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_res.h deleted file mode 100644 index 5c6797204f..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_res.h +++ /dev/null @@ -1,107 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_TREE_OCP_QP_RES_H_ -#define HPIPM_S_TREE_OCP_QP_RES_H_ - - - -#include -#include - -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_tree_ocp_qp_res - { - struct s_tree_ocp_qp_dim *dim; - struct blasfeo_svec *res_g; // q-residuals - struct blasfeo_svec *res_b; // b-residuals - struct blasfeo_svec *res_d; // d-residuals - struct blasfeo_svec *res_m; // m-residuals - float res_max[4]; // max of residuals - float res_mu; // mu-residual - hpipm_size_t memsize; - }; - - - -struct s_tree_ocp_qp_res_ws - { - struct blasfeo_svec *tmp_nbgM; // work space of size nbM+ngM - struct blasfeo_svec *tmp_nsM; // work space of size nsM - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_tree_ocp_qp_res_memsize(struct s_tree_ocp_qp_dim *ocp_dim); -// -void s_tree_ocp_qp_res_create(struct s_tree_ocp_qp_dim *ocp_dim, struct s_tree_ocp_qp_res *res, void *mem); -// -hpipm_size_t s_tree_ocp_qp_res_ws_memsize(struct s_tree_ocp_qp_dim *ocp_dim); -// -void s_tree_ocp_qp_res_ws_create(struct s_tree_ocp_qp_dim *ocp_dim, struct s_tree_ocp_qp_res_ws *ws, void *mem); -// -void s_tree_ocp_qp_res_get_all(struct s_tree_ocp_qp_res *res, float **res_r, float **res_q, float **res_ls, float **res_us, float **res_b, float **res_d_lb, float **res_d_ub, float **res_d_lg, float **res_d_ug, float **res_d_ls, float **res_d_us, float **res_m_lb, float **res_m_ub, float **res_m_lg, float **res_m_ug, float **res_m_ls, float **res_m_us); -// -void s_tree_ocp_qp_res_compute(struct s_tree_ocp_qp *qp, struct s_tree_ocp_qp_sol *qp_sol, struct s_tree_ocp_qp_res *res, struct s_tree_ocp_qp_res_ws *ws); -// -void s_tree_ocp_qp_res_compute_lin(struct s_tree_ocp_qp *qp, struct s_tree_ocp_qp_sol *qp_sol, struct s_tree_ocp_qp_sol *qp_step, struct s_tree_ocp_qp_res *res, struct s_tree_ocp_qp_res_ws *ws); -// -void s_tree_ocp_qp_res_compute_inf_norm(struct s_tree_ocp_qp_res *res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_S_TREE_OCP_QP_RES_H_ - - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_sol.h b/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_sol.h deleted file mode 100644 index 71e887675b..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_sol.h +++ /dev/null @@ -1,98 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_TREE_OCP_QP_SOL_H_ -#define HPIPM_S_TREE_OCP_QP_SOL_H_ - - - -#include -#include - -#include "hpipm_s_tree_ocp_qp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - -struct s_tree_ocp_qp_sol - { - struct s_tree_ocp_qp_dim *dim; - struct blasfeo_svec *ux; - struct blasfeo_svec *pi; - struct blasfeo_svec *lam; - struct blasfeo_svec *t; - void *misc; - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t s_tree_ocp_qp_sol_memsize(struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_sol_create(struct s_tree_ocp_qp_dim *dim, struct s_tree_ocp_qp_sol *qp_sol, void *memory); -// -void s_tree_ocp_qp_sol_get_all(struct s_tree_ocp_qp *qp, struct s_tree_ocp_qp_sol *qp_sol, float **u, float **x, float **ls, float **us, float **pi, float **lam_lb, float **lam_ub, float **lam_lg, float **lam_ug, float **lam_ls, float **lam_us); -// -void s_tree_ocp_qp_sol_get_u(int node, struct s_tree_ocp_qp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qp_sol_get_x(int node, struct s_tree_ocp_qp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qp_sol_get_sl(int node, struct s_tree_ocp_qp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qp_sol_get_su(int node, struct s_tree_ocp_qp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qp_sol_get_pi(int edge, struct s_tree_ocp_qp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qp_sol_get_lam_lb(int node, struct s_tree_ocp_qp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qp_sol_get_lam_ub(int node, struct s_tree_ocp_qp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qp_sol_get_lam_lg(int node, struct s_tree_ocp_qp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qp_sol_get_lam_ug(int node, struct s_tree_ocp_qp_sol *qp_sol, float *vec); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_TREE_OCP_QP_SOL_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_utils.h b/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_utils.h deleted file mode 100644 index ec1747568f..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_utils.h +++ /dev/null @@ -1,84 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_TREE_OCP_QP_UTILS_H_ -#define HPIPM_S_TREE_OCP_QP_UTILS_H_ - - - -#include -#include - -#include "hpipm_s_tree_ocp_qp_dim.h" -#include "hpipm_s_tree_ocp_qp.h" -#include "hpipm_s_tree_ocp_qp_sol.h" -#include "hpipm_s_tree_ocp_qp_ipm.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void s_tree_ocp_qp_dim_print(struct s_tree_ocp_qp_dim *qp_dim); -// -//void s_tree_ocp_qp_dim_codegen(char *file_name, char *mode, struct s_tree_ocp_qp_dim *qp_dim); -// -void s_tree_ocp_qp_print(struct s_tree_ocp_qp_dim *qp_dim, struct s_tree_ocp_qp *qp); -// -//void s_tree_ocp_qp_codegen(char *file_name, char *mode, struct s_tree_ocp_qp_dim *qp_dim, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_sol_print(struct s_tree_ocp_qp_dim *qp_dim, struct s_tree_ocp_qp_sol *ocp_qp_sol); -// -void s_tree_ocp_qp_ipm_arg_print(struct s_tree_ocp_qp_dim *qp_dim, struct s_tree_ocp_qp_ipm_arg *arg); -// -//void s_tree_ocp_qp_ipm_arg_codegen(char *file_name, char *mode, struct s_tree_ocp_qp_dim *qp_dim, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_res_print(struct s_tree_ocp_qp_dim *qp_dim, struct s_tree_ocp_qp_res *ocp_qp_res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_S_TREE_OCP_QP_UTILS_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_scenario_tree.h b/third_party/acados/include/hpipm/include/hpipm_scenario_tree.h deleted file mode 100644 index a3c77a670a..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_scenario_tree.h +++ /dev/null @@ -1,70 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_SCENARIO_TREE_H_ -#define HPIPM_SCENARIO_TREE_H_ - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct sctree - { - struct node *root; // pointer to root - int *kids; // pointer to array of kids - int Nn; // numer of nodes - int md; // number of realizations - int Nr; // robust horizion - int Nh; // control horizion - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t sctree_memsize(int md, int Nr, int Nh); -// -void sctree_create(int md, int Nr, int Nh, struct sctree *st, void *memory); -// -void sctree_cast_to_tree(struct sctree *st, struct tree *tt); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // HPIPM_SCENARIO_TREE_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_timing.h b/third_party/acados/include/hpipm/include/hpipm_timing.h deleted file mode 100644 index bd0f2dbcb3..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_timing.h +++ /dev/null @@ -1,67 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_TIMING_H_ -#define HPIPM_TIMING_H_ - - - -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -typedef blasfeo_timer hpipm_timer; - - - -// -void hpipm_tic(hpipm_timer *t); -// -double hpipm_toc(hpipm_timer *t); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_TIMING_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_tree.h b/third_party/acados/include/hpipm/include/hpipm_tree.h deleted file mode 100644 index f9d69ecddd..0000000000 --- a/third_party/acados/include/hpipm/include/hpipm_tree.h +++ /dev/null @@ -1,76 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - -#ifndef HPIPM_TREE_H_ -#define HPIPM_TREE_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct node - { - int *kids; // 64 bits - int idx; // 32 bits - int dad; // 32 bits - int nkids; // 32 bits - int stage; // 32 bits - int real; // 32 bits - int idxkid; // 32 bits // XXX needed ??? - // total 256 bits - }; - - - -struct tree - { - struct node *root; // pointer to root - int *kids; // pointer to array of kids - int Nn; // numer of nodes - hpipm_size_t memsize; - }; - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // HPIPM_TREE_H_ diff --git a/third_party/acados/include/qpOASES_e/Bounds.h b/third_party/acados/include/qpOASES_e/Bounds.h deleted file mode 100644 index 4e41c1d163..0000000000 --- a/third_party/acados/include/qpOASES_e/Bounds.h +++ /dev/null @@ -1,543 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/Bounds.h - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - * - * Declaration of the Bounds class designed to manage working sets of - * bounds within a QProblem. - */ - - -#ifndef QPOASES_BOUNDS_H -#define QPOASES_BOUNDS_H - - -#include - - -BEGIN_NAMESPACE_QPOASES - - -/** - * \brief Manages working sets of bounds (= box constraints). - * - * This class manages working sets of bounds (= box constraints) - * by storing index sets and other status information. - * - * \author Hans Joachim Ferreau - * \version 3.1embedded - * \date 2007-2015 - */ -typedef struct -{ - Indexlist *freee; /**< Index list of free variables. */ - Indexlist *fixed; /**< Index list of fixed variables. */ - - Indexlist *shiftedFreee; /**< Memory for shifting free variables. */ - Indexlist *shiftedFixed; /**< Memory for shifting fixed variables. */ - - Indexlist *rotatedFreee; /**< Memory for rotating free variables. */ - Indexlist *rotatedFixed; /**< Memory for rotating fixed variables. */ - - SubjectToType *type; /**< Type of bounds. */ - SubjectToStatus *status; /**< Status of bounds. */ - - SubjectToType *typeTmp; /**< Temp memory for type of bounds. */ - SubjectToStatus *statusTmp; /**< Temp memory for status of bounds. */ - - BooleanType noLower; /**< This flag indicates if there is no lower bound on any variable. */ - BooleanType noUpper; /**< This flag indicates if there is no upper bound on any variable. */ - - int n; /**< Total number of bounds. */ -} Bounds; - -int Bounds_calculateMemorySize( int n); - -char *Bounds_assignMemory(int n, Bounds **mem, void *raw_memory); - -Bounds *Bounds_createMemory( int n ); - -/** Constructor which takes the number of bounds. */ -void BoundsCON( Bounds* _THIS, - int _n /**< Number of bounds. */ - ); - -/** Copies all members from given rhs object. - * \return SUCCESSFUL_RETURN */ -void BoundsCPY( Bounds* FROM, - Bounds* TO - ); - - -/** Initialises object with given number of bounds. - * \return SUCCESSFUL_RETURN \n - RET_INVALID_ARGUMENTS */ -returnValue Bounds_init( Bounds* _THIS, - int _n /**< Number of bounds. */ - ); - - -/** Initially adds number of a new (i.e. not yet in the list) bound to - * given index set. - * \return SUCCESSFUL_RETURN \n - RET_SETUP_BOUND_FAILED \n - RET_INDEX_OUT_OF_BOUNDS \n - RET_INVALID_ARGUMENTS */ -returnValue Bounds_setupBound( Bounds* _THIS, - int number, /**< Number of new bound. */ - SubjectToStatus _status /**< Status of new bound. */ - ); - -/** Initially adds all numbers of new (i.e. not yet in the list) bounds to - * to the index set of free bounds; the order depends on the SujectToType - * of each index. - * \return SUCCESSFUL_RETURN \n - RET_SETUP_BOUND_FAILED */ -returnValue Bounds_setupAllFree( Bounds* _THIS - ); - -/** Initially adds all numbers of new (i.e. not yet in the list) bounds to - * to the index set of fixed bounds (on their lower bounds); - * the order depends on the SujectToType of each index. - * \return SUCCESSFUL_RETURN \n - RET_SETUP_BOUND_FAILED */ -returnValue Bounds_setupAllLower( Bounds* _THIS - ); - -/** Initially adds all numbers of new (i.e. not yet in the list) bounds to - * to the index set of fixed bounds (on their upper bounds); - * the order depends on the SujectToType of each index. - * \return SUCCESSFUL_RETURN \n - RET_SETUP_BOUND_FAILED */ -returnValue Bounds_setupAllUpper( Bounds* _THIS - ); - - -/** Moves index of a bound from index list of fixed to that of free bounds. - * \return SUCCESSFUL_RETURN \n - RET_MOVING_BOUND_FAILED \n - RET_INDEX_OUT_OF_BOUNDS */ -returnValue Bounds_moveFixedToFree( Bounds* _THIS, - int number /**< Number of bound to be freed. */ - ); - -/** Moves index of a bound from index list of free to that of fixed bounds. - * \return SUCCESSFUL_RETURN \n - RET_MOVING_BOUND_FAILED \n - RET_INDEX_OUT_OF_BOUNDS */ -returnValue Bounds_moveFreeToFixed( Bounds* _THIS, - int number, /**< Number of bound to be fixed. */ - SubjectToStatus _status /**< Status of bound to be fixed. */ - ); - -/** Flip fixed bound. - * \return SUCCESSFUL_RETURN \n - RET_MOVING_BOUND_FAILED \n - RET_INDEX_OUT_OF_BOUNDS */ -returnValue Bounds_flipFixed( Bounds* _THIS, - int number - ); - -/** Swaps the indices of two free bounds within the index set. - * \return SUCCESSFUL_RETURN \n - RET_SWAPINDEX_FAILED */ -returnValue Bounds_swapFree( Bounds* _THIS, - int number1, /**< Number of first bound. */ - int number2 /**< Number of second bound. */ - ); - - -/** Returns number of variables. - * \return Number of variables. */ -static inline int Bounds_getNV( Bounds* _THIS - ); - -/** Returns number of implicitly fixed variables. - * \return Number of implicitly fixed variables. */ -static inline int Bounds_getNFV( Bounds* _THIS - ); - -/** Returns number of bounded (but possibly free) variables. - * \return Number of bounded (but possibly free) variables. */ -static inline int Bounds_getNBV( Bounds* _THIS - ); - -/** Returns number of unbounded variables. - * \return Number of unbounded variables. */ -static inline int Bounds_getNUV( Bounds* _THIS - ); - -/** Returns number of free variables. - * \return Number of free variables. */ -static inline int Bounds_getNFR( Bounds* _THIS - ); - -/** Returns number of fixed variables. - * \return Number of fixed variables. */ -static inline int Bounds_getNFX( Bounds* _THIS - ); - - -/** Returns a pointer to free variables index list. - * \return Pointer to free variables index list. */ -static inline Indexlist* Bounds_getFree( Bounds* _THIS - ); - -/** Returns a pointer to fixed variables index list. - * \return Pointer to fixed variables index list. */ -static inline Indexlist* Bounds_getFixed( Bounds* _THIS - ); - - -/** Returns number of bounds with given SubjectTo type. - * \return Number of bounds with given type. */ -static inline int Bounds_getNumberOfType( Bounds* _THIS, - SubjectToType _type /**< Type of bound. */ - ); - - -/** Returns type of bound. - * \return Type of bound \n - RET_INDEX_OUT_OF_BOUNDS */ -static inline SubjectToType Bounds_getType( Bounds* _THIS, - int i /**< Number of bound. */ - ); - -/** Returns status of bound. - * \return Status of bound \n - ST_UNDEFINED */ -static inline SubjectToStatus Bounds_getStatus( Bounds* _THIS, - int i /**< Number of bound. */ - ); - - -/** Sets type of bound. - * \return SUCCESSFUL_RETURN \n - RET_INDEX_OUT_OF_BOUNDS */ -static inline returnValue Bounds_setType( Bounds* _THIS, - int i, /**< Number of bound. */ - SubjectToType value /**< Type of bound. */ - ); - -/** Sets status of bound. - * \return SUCCESSFUL_RETURN \n - RET_INDEX_OUT_OF_BOUNDS */ -static inline returnValue Bounds_setStatus( Bounds* _THIS, - int i, /**< Number of bound. */ - SubjectToStatus value /**< Status of bound. */ - ); - - -/** Sets status of lower bounds. */ -static inline void Bounds_setNoLower( Bounds* _THIS, - BooleanType _status /**< Status of lower bounds. */ - ); - -/** Sets status of upper bounds. */ -static inline void Bounds_setNoUpper( Bounds* _THIS, - BooleanType _status /**< Status of upper bounds. */ - ); - - -/** Returns status of lower bounds. - * \return BT_TRUE if there is no lower bound on any variable. */ -static inline BooleanType Bounds_hasNoLower( Bounds* _THIS - ); - -/** Returns status of upper bounds. - * \return BT_TRUE if there is no upper bound on any variable. */ -static inline BooleanType Bounds_hasNoUpper( Bounds* _THIS - ); - - -/** Shifts forward type and status of all bounds by a given - * offset. This offset has to lie within the range [0,n/2] and has to - * be an integer divisor of the total number of bounds n. - * Type and status of the first \ bounds is thrown away, - * type and status of the last \ bounds is doubled, - * e.g. for offset = 2: \n - * shift( {b1,b2,b3,b4,b5,b6} ) = {b3,b4,b5,b6,b5,b6} - * \return SUCCESSFUL_RETURN \n - RET_INDEX_OUT_OF_BOUNDS \n - RET_INVALID_ARGUMENTS \n - RET_SHIFTING_FAILED */ -returnValue Bounds_shift( Bounds* _THIS, - int offset /**< Shift offset within the range [0,n/2] and integer divisor of n. */ - ); - -/** Rotates forward type and status of all bounds by a given - * offset. This offset has to lie within the range [0,n]. - * Example for offset = 2: \n - * rotate( {b1,b2,b3,b4,b5,b6} ) = {b3,b4,b5,b6,b1,b2} - * \return SUCCESSFUL_RETURN \n - RET_INDEX_OUT_OF_BOUNDS \n - RET_ROTATING_FAILED */ -returnValue Bounds_rotate( Bounds* _THIS, - int offset /**< Rotation offset within the range [0,n]. */ - ); - - -/** Prints information on bounds object - * (in particular, lists of free and fixed bounds. - * \return SUCCESSFUL_RETURN \n - RET_INDEXLIST_CORRUPTED */ -returnValue Bounds_print( Bounds* _THIS - ); - - -/** Initially adds all numbers of new (i.e. not yet in the list) bounds to - * to the index set corresponding to the desired status; - * the order depends on the SujectToType of each index. - * \return SUCCESSFUL_RETURN \n - RET_SETUP_BOUND_FAILED */ -returnValue Bounds_setupAll( Bounds* _THIS, - SubjectToStatus _status /**< Desired initial status for all bounds. */ - ); - - -/** Adds the index of a new bound to index set. - * \return SUCCESSFUL_RETURN \n - RET_ADDINDEX_FAILED \n - RET_INVALID_ARGUMENTS */ -returnValue Bounds_addIndex( Bounds* _THIS, - Indexlist* const indexlist, /**< Index list to which the new index shall be added. */ - int newnumber, /**< Number of new bound. */ - SubjectToStatus newstatus /**< Status of new bound. */ - ); - -/** Removes the index of a bound from index set. - * \return SUCCESSFUL_RETURN \n - RET_REMOVEINDEX_FAILED \n - RET_INVALID_ARGUMENTS */ -returnValue Bounds_removeIndex( Bounds* _THIS, - Indexlist* const indexlist, /**< Index list from which the new index shall be removed. */ - int removenumber /**< Number of bound to be removed. */ - ); - -/** Swaps the indices of two constraints or bounds within the index set. - * \return SUCCESSFUL_RETURN \n - RET_SWAPINDEX_FAILED \n - RET_INVALID_ARGUMENTS */ -returnValue Bounds_swapIndex( Bounds* _THIS, - Indexlist* const indexlist, /**< Index list in which the indices shold be swapped. */ - int number1, /**< Number of first bound. */ - int number2 /**< Number of second bound. */ - ); - - - -/* - * g e t N u m b e r O f T y p e - */ -static inline int Bounds_getNumberOfType( Bounds* _THIS, SubjectToType _type ) -{ - int i; - int numberOfType = 0; - - if ( _THIS->type != 0 ) - { - for( i=0; i<_THIS->n; ++i ) - if ( _THIS->type[i] == _type ) - ++numberOfType; - } - - return numberOfType; -} - - -/* - * g e t T y p e - */ -static inline SubjectToType Bounds_getType( Bounds* _THIS, int i ) -{ - if ( ( i >= 0 ) && ( i < _THIS->n ) ) - return _THIS->type[i]; - - return ST_UNKNOWN; -} - - -/* - * g e t S t a t u s - */ -static inline SubjectToStatus Bounds_getStatus( Bounds* _THIS, int i ) -{ - if ( ( i >= 0 ) && ( i < _THIS->n ) ) - return _THIS->status[i]; - - return ST_UNDEFINED; -} - - -/* - * s e t T y p e - */ -static inline returnValue Bounds_setType( Bounds* _THIS, int i, SubjectToType value ) -{ - if ( ( i >= 0 ) && ( i < _THIS->n ) ) - { - _THIS->type[i] = value; - return SUCCESSFUL_RETURN; - } - else - return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); -} - - -/* - * s e t S t a t u s - */ -static inline returnValue Bounds_setStatus( Bounds* _THIS, int i, SubjectToStatus value ) -{ - if ( ( i >= 0 ) && ( i < _THIS->n ) ) - { - _THIS->status[i] = value; - return SUCCESSFUL_RETURN; - } - else - return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); -} - - -/* - * s e t N o L o w e r - */ -static inline void Bounds_setNoLower( Bounds* _THIS, BooleanType _status ) -{ - _THIS->noLower = _status; -} - - -/* - * s e t N o U p p e r - */ -static inline void Bounds_setNoUpper( Bounds* _THIS, BooleanType _status ) -{ - _THIS->noUpper = _status; -} - - -/* - * h a s N o L o w e r - */ -static inline BooleanType Bounds_hasNoLower( Bounds* _THIS ) -{ - return _THIS->noLower; -} - - -/* - * h a s N o U p p p e r - */ -static inline BooleanType Bounds_hasNoUpper( Bounds* _THIS ) -{ - return _THIS->noUpper; -} - - - -/* - * g e t N V - */ -static inline int Bounds_getNV( Bounds* _THIS ) -{ - return _THIS->n; -} - - -/* - * g e t N F V - */ -static inline int Bounds_getNFV( Bounds* _THIS ) -{ - return Bounds_getNumberOfType( _THIS,ST_EQUALITY ); -} - - -/* - * g e t N B V - */ -static inline int Bounds_getNBV( Bounds* _THIS ) -{ - return Bounds_getNumberOfType( _THIS,ST_BOUNDED ); -} - - -/* - * g e t N U V - */ -static inline int Bounds_getNUV( Bounds* _THIS ) -{ - return Bounds_getNumberOfType( _THIS,ST_UNBOUNDED ); -} - - -/* - * g e t N F R - */ -static inline int Bounds_getNFR( Bounds* _THIS ) -{ - return Indexlist_getLength( _THIS->freee ); -} - - -/* - * g e t N F X - */ -static inline int Bounds_getNFX( Bounds* _THIS ) -{ - return Indexlist_getLength( _THIS->fixed ); -} - - -/* - * g e t F r e e - */ -static inline Indexlist* Bounds_getFree( Bounds* _THIS ) -{ - return _THIS->freee; -} - - -/* - * g e t F i x e d - */ -static inline Indexlist* Bounds_getFixed( Bounds* _THIS ) -{ - return _THIS->fixed; -} - - -END_NAMESPACE_QPOASES - -#endif /* QPOASES_BOUNDS_H */ - - -/* - * end of file - */ diff --git a/third_party/acados/include/qpOASES_e/Constants.h b/third_party/acados/include/qpOASES_e/Constants.h deleted file mode 100644 index 13c777d75b..0000000000 --- a/third_party/acados/include/qpOASES_e/Constants.h +++ /dev/null @@ -1,134 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/Constants.h - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - * - * Definition of all global constants. - */ - - -#ifndef QPOASES_CONSTANTS_H -#define QPOASES_CONSTANTS_H - - -#include - -#ifdef __CODE_GENERATION__ - - #define CONVERTTOSTRINGAUX(x) #x - #define CONVERTTOSTRING(x) CONVERTTOSTRINGAUX(x) - - #ifndef QPOASES_CUSTOM_INTERFACE - #include "acado_qpoases3_interface.h" - #else - #include CONVERTTOSTRING(QPOASES_CUSTOM_INTERFACE) - #endif - -#endif - - -BEGIN_NAMESPACE_QPOASES - - -#ifndef __EXTERNAL_DIMENSIONS__ - - /*#define QPOASES_NVMAX 50 - #define QPOASES_NCMAX 100*/ - #define QPOASES_NVMAX 287 - #define QPOASES_NCMAX 709 - -#endif /* __EXTERNAL_DIMENSIONS__ */ - - -/** Maximum number of variables within a QP formulation. - * Note: this value has to be positive! */ -#define NVMAX QPOASES_NVMAX - -/** Maximum number of constraints within a QP formulation. - * Note: this value has to be positive! */ -#define NCMAX QPOASES_NCMAX - -#if ( QPOASES_NVMAX > QPOASES_NCMAX ) -#define NVCMAX QPOASES_NVMAX -#else -#define NVCMAX QPOASES_NCMAX -#endif - -#if ( QPOASES_NVMAX > QPOASES_NCMAX ) -#define NVCMIN QPOASES_NCMAX -#else -#define NVCMIN QPOASES_NVMAX -#endif - - -/** Maximum number of QPs in a sequence solved by means of the OQP interface. - * Note: this value has to be positive! */ -#define NQPMAX 1000 - - -/** Numerical value of machine precision (min eps, s.t. 1+eps > 1). - * Note: this value has to be positive! */ -#ifndef __CODE_GENERATION__ - - #ifdef __USE_SINGLE_PRECISION__ - static const real_t QPOASES_EPS = 1.193e-07; - #else - static const real_t QPOASES_EPS = 2.221e-16; - #endif /* __USE_SINGLE_PRECISION__ */ - -#endif /* __CODE_GENERATION__ */ - - -/** Numerical value of zero (for situations in which it would be - * unreasonable to compare with 0.0). - * Note: this value has to be positive! */ -static const real_t QPOASES_ZERO = 1.0e-25; - -/** Numerical value of infinity (e.g. for non-existing bounds). - * Note: this value has to be positive! */ -static const real_t QPOASES_INFTY = 1.0e20; - -/** Tolerance to used for isEqual, isZero etc. - * Note: this value has to be positive! */ -static const real_t QPOASES_TOL = 1.0e-25; - - -/** Maximum number of characters within a string. - * Note: this value should be at least 41! */ -#define QPOASES_MAX_STRING_LENGTH 160 - - -END_NAMESPACE_QPOASES - - -#endif /* QPOASES_CONSTANTS_H */ - - -/* - * end of file - */ diff --git a/third_party/acados/include/qpOASES_e/ConstraintProduct.h b/third_party/acados/include/qpOASES_e/ConstraintProduct.h deleted file mode 100644 index eb5400c6cb..0000000000 --- a/third_party/acados/include/qpOASES_e/ConstraintProduct.h +++ /dev/null @@ -1,62 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/ConstraintProduct.h - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches (thanks to D. Kwame Minde Kufoalor) - * \version 3.1embedded - * \date 2009-2015 - * - * Declaration of the ConstraintProduct interface which allows to specify a - * user-defined function for evaluating the constraint product at the - * current iterate to speed-up QP solution in case of a specially structured - * constraint matrix. - */ - - - -#ifndef QPOASES_CONSTRAINT_PRODUCT_H -#define QPOASES_CONSTRAINT_PRODUCT_H - - -BEGIN_NAMESPACE_QPOASES - - -/** - * \brief Interface for specifying user-defined evaluations of constraint products. - * - * An interface which allows to specify a user-defined function for evaluating the - * constraint product at the current iterate to speed-up QP solution in case - * of a specially structured constraint matrix. - * - * \author Hans Joachim Ferreau (thanks to Kwame Minde Kufoalor) - * \version 3.1embedded - * \date 2009-2015 - */ -typedef int(*ConstraintProduct)( int, const real_t* const, real_t* const ); - - -END_NAMESPACE_QPOASES - -#endif /* QPOASES_CONSTRAINT_PRODUCT_H */ diff --git a/third_party/acados/include/qpOASES_e/Constraints.h b/third_party/acados/include/qpOASES_e/Constraints.h deleted file mode 100644 index 8aca10d5d9..0000000000 --- a/third_party/acados/include/qpOASES_e/Constraints.h +++ /dev/null @@ -1,535 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/Constraints.h - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - * - * Declaration of the Constraints class designed to manage working sets of - * constraints within a QProblem. - */ - - -#ifndef QPOASES_CONSTRAINTS_H -#define QPOASES_CONSTRAINTS_H - - -#include - - -BEGIN_NAMESPACE_QPOASES - - -/** - * \brief Manages working sets of constraints. - * - * This class manages working sets of constraints by storing - * index sets and other status information. - * - * \author Hans Joachim Ferreau - * \version 3.1embedded - * \date 2007-2015 - */ -typedef struct -{ - Indexlist *active; /**< Index list of active constraints. */ - Indexlist *inactive; /**< Index list of inactive constraints. */ - - Indexlist *shiftedActive; /**< Memory for shifting active constraints. */ - Indexlist *shiftedInactive; /**< Memory for shifting inactive constraints. */ - - Indexlist *rotatedActive; /**< Memory for rotating active constraints. */ - Indexlist *rotatedInactive; /**< Memory for rotating inactive constraints. */ - - SubjectToType *type; /**< Type of constraints. */ - SubjectToStatus *status; /**< Status of constraints. */ - - SubjectToType *typeTmp; /**< Temp memory for type of constraints. */ - SubjectToStatus *statusTmp; /**< Temp memory for status of constraints. */ - - BooleanType noLower; /**< This flag indicates if there is no lower bound on any variable. */ - BooleanType noUpper; /**< This flag indicates if there is no upper bound on any variable. */ - - int n; /**< Total number of constraints. */ -} Constraints; - -int Constraints_calculateMemorySize( int n); - -char *Constraints_assignMemory(int n, Constraints **mem, void *raw_memory); - -Constraints *Constraints_createMemory( int n ); - -/** Constructor which takes the number of constraints. */ -void ConstraintsCON( Constraints* _THIS, - int _n /**< Number of constraints. */ - ); - -/** Copies all members from given rhs object. - * \return SUCCESSFUL_RETURN */ -void ConstraintsCPY( Constraints* FROM, - Constraints* TO - ); - - -/** Initialises object with given number of constraints. - * \return SUCCESSFUL_RETURN \n - RET_INVALID_ARGUMENTS */ -returnValue Constraints_init( Constraints* _THIS, - int _n /**< Number of constraints. */ - ); - - -/** Initially adds number of a new (i.e. not yet in the list) constraint to - * a given index set. - * \return SUCCESSFUL_RETURN \n - RET_SETUP_CONSTRAINT_FAILED \n - RET_INDEX_OUT_OF_BOUNDS \n - RET_INVALID_ARGUMENTS */ -returnValue Constraints_setupConstraint( Constraints* _THIS, - int number, /**< Number of new constraint. */ - SubjectToStatus _status /**< Status of new constraint. */ - ); - -/** Initially adds all enabled numbers of new (i.e. not yet in the list) constraints to - * to the index set of inactive constraints; the order depends on the SujectToType - * of each index. Only disabled constraints are added to index set of disabled constraints! - * \return SUCCESSFUL_RETURN \n - RET_SETUP_CONSTRAINT_FAILED */ -returnValue Constraints_setupAllInactive( Constraints* _THIS - ); - -/** Initially adds all enabled numbers of new (i.e. not yet in the list) constraints to - * to the index set of active constraints (on their lower bounds); the order depends on the SujectToType - * of each index. Only disabled constraints are added to index set of disabled constraints! - * \return SUCCESSFUL_RETURN \n - RET_SETUP_CONSTRAINT_FAILED */ -returnValue Constraints_setupAllLower( Constraints* _THIS - ); - -/** Initially adds all enabled numbers of new (i.e. not yet in the list) constraints to - * to the index set of active constraints (on their upper bounds); the order depends on the SujectToType - * of each index. Only disabled constraints are added to index set of disabled constraints! - * \return SUCCESSFUL_RETURN \n - RET_SETUP_CONSTRAINT_FAILED */ -returnValue Constraints_setupAllUpper( Constraints* _THIS - ); - - -/** Moves index of a constraint from index list of active to that of inactive constraints. - * \return SUCCESSFUL_RETURN \n - RET_MOVING_CONSTRAINT_FAILED */ -returnValue Constraints_moveActiveToInactive( Constraints* _THIS, - int number /**< Number of constraint to become inactive. */ - ); - -/** Moves index of a constraint from index list of inactive to that of active constraints. - * \return SUCCESSFUL_RETURN \n - RET_MOVING_CONSTRAINT_FAILED */ -returnValue Constraints_moveInactiveToActive( Constraints* _THIS, - int number, /**< Number of constraint to become active. */ - SubjectToStatus _status /**< Status of constraint to become active. */ - ); - -/** Flip fixed constraint. - * \return SUCCESSFUL_RETURN \n - RET_MOVING_CONSTRAINT_FAILED \n - RET_INDEX_OUT_OF_BOUNDS */ -returnValue Constraints_flipFixed( Constraints* _THIS, - int number - ); - - -/** Returns the number of constraints. - * \return Number of constraints. */ -static inline int Constraints_getNC( Constraints* _THIS - ); - -/** Returns the number of implicit equality constraints. - * \return Number of implicit equality constraints. */ -static inline int Constraints_getNEC( Constraints* _THIS - ); - -/** Returns the number of "real" inequality constraints. - * \return Number of "real" inequality constraints. */ -static inline int Constraints_getNIC( Constraints* _THIS - ); - -/** Returns the number of unbounded constraints (i.e. without any bounds). - * \return Number of unbounded constraints (i.e. without any bounds). */ -static inline int Constraints_getNUC( Constraints* _THIS - ); - -/** Returns the number of active constraints. - * \return Number of active constraints. */ -static inline int Constraints_getNAC( Constraints* _THIS - ); - -/** Returns the number of inactive constraints. - * \return Number of inactive constraints. */ -static inline int Constraints_getNIAC( Constraints* _THIS - ); - - -/** Returns a pointer to active constraints index list. - * \return Pointer to active constraints index list. */ -static inline Indexlist* Constraints_getActive( Constraints* _THIS - ); - -/** Returns a pointer to inactive constraints index list. - * \return Pointer to inactive constraints index list. */ -static inline Indexlist* Constraints_getInactive( Constraints* _THIS - ); - - -/** Returns number of constraints with given SubjectTo type. - * \return Number of constraints with given type. */ -static inline int Constraints_getNumberOfType( Constraints* _THIS, - SubjectToType _type /**< Type of constraints' bound. */ - ); - - -/** Returns type of constraints' bound. - * \return Type of constraints' bound \n - RET_INDEX_OUT_OF_BOUNDS */ -static inline SubjectToType Constraints_getType( Constraints* _THIS, - int i /**< Number of constraints' bound. */ - ); - -/** Returns status of constraints' bound. - * \return Status of constraints' bound \n - ST_UNDEFINED */ -static inline SubjectToStatus Constraints_getStatus( Constraints* _THIS, - int i /**< Number of constraints' bound. */ - ); - - -/** Sets type of constraints' bound. - * \return SUCCESSFUL_RETURN \n - RET_INDEX_OUT_OF_BOUNDS */ -static inline returnValue Constraints_setType( Constraints* _THIS, - int i, /**< Number of constraints' bound. */ - SubjectToType value /**< Type of constraints' bound. */ - ); - -/** Sets status of constraints' bound. - * \return SUCCESSFUL_RETURN \n - RET_INDEX_OUT_OF_BOUNDS */ -static inline returnValue Constraints_setStatus( Constraints* _THIS, - int i, /**< Number of constraints' bound. */ - SubjectToStatus value /**< Status of constraints' bound. */ - ); - - -/** Sets status of lower constraints' bounds. */ -static inline void Constraints_setNoLower( Constraints* _THIS, - BooleanType _status /**< Status of lower constraints' bounds. */ - ); - -/** Sets status of upper constraints' bounds. */ -static inline void Constraints_setNoUpper( Constraints* _THIS, - BooleanType _status /**< Status of upper constraints' bounds. */ - ); - - -/** Returns status of lower constraints' bounds. - * \return BT_TRUE if there is no lower constraints' bound on any variable. */ -static inline BooleanType Constraints_hasNoLower( Constraints* _THIS - ); - -/** Returns status of upper bounds. - * \return BT_TRUE if there is no upper constraints' bound on any variable. */ -static inline BooleanType Constraints_hasNoUpper( Constraints* _THIS - ); - - -/** Shifts forward type and status of all constraints by a given - * offset. This offset has to lie within the range [0,n/2] and has to - * be an integer divisor of the total number of constraints n. - * Type and status of the first \ constraints is thrown away, - * type and status of the last \ constraints is doubled, - * e.g. for offset = 2: \n - * shift( {c/b1,c/b2,c/b3,c/b4,c/b5,c/b6} ) = {c/b3,c/b4,c/b5,c/b6,c/b5,c/b6} - * \return SUCCESSFUL_RETURN \n - RET_INDEX_OUT_OF_BOUNDS \n - RET_INVALID_ARGUMENTS \n - RET_SHIFTING_FAILED */ -returnValue Constraints_shift( Constraints* _THIS, - int offset /**< Shift offset within the range [0,n/2] and integer divisor of n. */ - ); - -/** Rotates forward type and status of all constraints by a given - * offset. This offset has to lie within the range [0,n]. - * Example for offset = 2: \n - * rotate( {c1,c2,c3,c4,c5,c6} ) = {c3,c4,c5,c6,c1,c2} - * \return SUCCESSFUL_RETURN \n - RET_INDEX_OUT_OF_BOUNDS \n - RET_ROTATING_FAILED */ -returnValue Constraints_rotate( Constraints* _THIS, - int offset /**< Rotation offset within the range [0,n]. */ - ); - - -/** Prints information on constraints object - * (in particular, lists of inactive and active constraints. - * \return SUCCESSFUL_RETURN \n - RET_INDEXLIST_CORRUPTED */ -returnValue Constraints_print( Constraints* _THIS - ); - - -/** Initially adds all numbers of new (i.e. not yet in the list) bounds to - * to the index set corresponding to the desired status; - * the order depends on the SujectToType of each index. - * \return SUCCESSFUL_RETURN \n - RET_SETUP_CONSTRAINT_FAILED */ -returnValue Constraints_setupAll( Constraints* _THIS, - SubjectToStatus _status /**< Desired initial status for all bounds. */ - ); - - -/** Adds the index of a new constraint to index set. - * \return SUCCESSFUL_RETURN \n - RET_ADDINDEX_FAILED \n - RET_INVALID_ARGUMENTS */ -returnValue Constraints_addIndex( Constraints* _THIS, - Indexlist* const indexlist, /**< Index list to which the new index shall be added. */ - int newnumber, /**< Number of new constraint. */ - SubjectToStatus newstatus /**< Status of new constraint. */ - ); - -/** Removes the index of a constraint from index set. - * \return SUCCESSFUL_RETURN \n - RET_REMOVEINDEX_FAILED \n - RET_INVALID_ARGUMENTS */ -returnValue Constraints_removeIndex( Constraints* _THIS, - Indexlist* const indexlist, /**< Index list from which the new index shall be removed. */ - int removenumber /**< Number of constraint to be removed. */ - ); - -/** Swaps the indices of two constraints or bounds within the index set. - * \return SUCCESSFUL_RETURN \n - RET_SWAPINDEX_FAILED \n - RET_INVALID_ARGUMENTS */ -returnValue Constraints_swapIndex( Constraints* _THIS, - Indexlist* const indexlist, /**< Index list in which the indices shold be swapped. */ - int number1, /**< Number of first constraint. */ - int number2 /**< Number of second constraint. */ - ); - - - -/* - * g e t N u m b e r O f T y p e - */ -static inline int Constraints_getNumberOfType( Constraints* _THIS, SubjectToType _type ) -{ - int i; - int numberOfType = 0; - - if ( _THIS->type != 0 ) - { - for( i=0; i<_THIS->n; ++i ) - if ( _THIS->type[i] == _type ) - ++numberOfType; - } - - return numberOfType; -} - - -/* - * g e t T y p e - */ -static inline SubjectToType Constraints_getType( Constraints* _THIS, int i ) -{ - if ( ( i >= 0 ) && ( i < _THIS->n ) ) - return _THIS->type[i]; - - return ST_UNKNOWN; -} - - -/* - * g e t S t a t u s - */ -static inline SubjectToStatus Constraints_getStatus( Constraints* _THIS, int i ) -{ - if ( ( i >= 0 ) && ( i < _THIS->n ) ) - return _THIS->status[i]; - - return ST_UNDEFINED; -} - - -/* - * s e t T y p e - */ -static inline returnValue Constraints_setType( Constraints* _THIS, int i, SubjectToType value ) -{ - if ( ( i >= 0 ) && ( i < _THIS->n ) ) - { - _THIS->type[i] = value; - return SUCCESSFUL_RETURN; - } - else - return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); -} - - -/* - * s e t S t a t u s - */ -static inline returnValue Constraints_setStatus( Constraints* _THIS, int i, SubjectToStatus value ) -{ - if ( ( i >= 0 ) && ( i < _THIS->n ) ) - { - _THIS->status[i] = value; - return SUCCESSFUL_RETURN; - } - else - return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); -} - - -/* - * s e t N o L o w e r - */ -static inline void Constraints_setNoLower( Constraints* _THIS, BooleanType _status ) -{ - _THIS->noLower = _status; -} - - -/* - * s e t N o U p p e r - */ -static inline void Constraints_setNoUpper( Constraints* _THIS, BooleanType _status ) -{ - _THIS->noUpper = _status; -} - - -/* - * h a s N o L o w e r - */ -static inline BooleanType Constraints_hasNoLower( Constraints* _THIS ) -{ - return _THIS->noLower; -} - - -/* - * h a s N o U p p p e r - */ -static inline BooleanType Constraints_hasNoUpper( Constraints* _THIS ) -{ - return _THIS->noUpper; -} - - - -/* - * g e t N C - */ -static inline int Constraints_getNC( Constraints* _THIS ) -{ - return _THIS->n; -} - - -/* - * g e t N E C - */ -static inline int Constraints_getNEC( Constraints* _THIS ) -{ - return Constraints_getNumberOfType( _THIS,ST_EQUALITY ); -} - - -/* - * g e t N I C - */ -static inline int Constraints_getNIC( Constraints* _THIS ) -{ - return Constraints_getNumberOfType( _THIS,ST_BOUNDED ); -} - - -/* - * g e t N U C - */ -static inline int Constraints_getNUC( Constraints* _THIS ) -{ - return Constraints_getNumberOfType( _THIS,ST_UNBOUNDED ); -} - - -/* - * g e t N A C - */ -static inline int Constraints_getNAC( Constraints* _THIS ) -{ - return Indexlist_getLength( _THIS->active ); -} - - -/* - * g e t N I A C - */ -static inline int Constraints_getNIAC( Constraints* _THIS ) -{ - return Indexlist_getLength( _THIS->inactive ); -} - - - -/* - * g e t A c t i v e - */ -static inline Indexlist* Constraints_getActive( Constraints* _THIS ) -{ - return _THIS->active; -} - - -/* - * g e t I n a c t i v e - */ -static inline Indexlist* Constraints_getInactive( Constraints* _THIS ) -{ - return _THIS->inactive; -} - - -END_NAMESPACE_QPOASES - - -#endif /* QPOASES_CONSTRAINTS_H */ - - -/* - * end of file - */ diff --git a/third_party/acados/include/qpOASES_e/Flipper.h b/third_party/acados/include/qpOASES_e/Flipper.h deleted file mode 100644 index 63526a30f3..0000000000 --- a/third_party/acados/include/qpOASES_e/Flipper.h +++ /dev/null @@ -1,129 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/Flipper.h - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - * - * Declaration of the Options class designed to manage user-specified - * options for solving a QProblem. - */ - - -#ifndef QPOASES_FLIPPER_H -#define QPOASES_FLIPPER_H - - -#include -#include - - -BEGIN_NAMESPACE_QPOASES - - -/** - * \brief Auxiliary class for storing a copy of the current matrix factorisations. - * - * This auxiliary class stores a copy of the current matrix factorisations. It - * is used by the classe QProblemB and QProblem in case flipping bounds are enabled. - * - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - */ -typedef struct -{ - Bounds *bounds; /**< Data structure for problem's bounds. */ - Constraints *constraints; /**< Data structure for problem's constraints. */ - - real_t *R; /**< Cholesky factor of H (i.e. H = R^T*R). */ - real_t *Q; /**< Orthonormal quadratic matrix, A = [0 T]*Q'. */ - real_t *T; /**< Reverse triangular matrix, A = [0 T]*Q'. */ - - unsigned int nV; /**< Number of variables. */ - unsigned int nC; /**< Number of constraints. */ -} Flipper; - -int Flipper_calculateMemorySize( unsigned int nV, unsigned int nC ); - -char *Flipper_assignMemory( unsigned int nV, unsigned int nC, Flipper **mem, void *raw_memory ); - -Flipper *Flipper_createMemory( unsigned int nV, unsigned int nC ); - -/** Constructor which takes the number of bounds and constraints. */ -void FlipperCON( Flipper* _THIS, - unsigned int _nV, /**< Number of bounds. */ - unsigned int _nC /**< Number of constraints. */ - ); - -/** Copy constructor (deep copy). */ -void FlipperCPY( Flipper* FROM, - Flipper* TO - ); - -/** Initialises object with given number of bounds and constraints. - * \return SUCCESSFUL_RETURN \n - RET_INVALID_ARGUMENTS */ -returnValue Flipper_init( Flipper* _THIS, - unsigned int _nV, /**< Number of bounds. */ - unsigned int _nC /**< Number of constraints. */ - ); - - -/** Copies current values to non-null arguments (assumed to be allocated with consistent size). - * \return SUCCESSFUL_RETURN */ -returnValue Flipper_get( Flipper* _THIS, - Bounds* const _bounds, /**< Pointer to new bounds. */ - real_t* const R, /**< New matrix R. */ - Constraints* const _constraints, /**< Pointer to new constraints. */ - real_t* const _Q, /**< New matrix Q. */ - real_t* const _T /**< New matrix T. */ - ); - -/** Assigns new values to non-null arguments. - * \return SUCCESSFUL_RETURN */ -returnValue Flipper_set( Flipper* _THIS, - const Bounds* const _bounds, /**< Pointer to new bounds. */ - const real_t* const _R, /**< New matrix R. */ - const Constraints* const _constraints, /**< Pointer to new constraints. */ - const real_t* const _Q, /**< New matrix Q. */ - const real_t* const _T /**< New matrix T. */ - ); - -/** Returns dimension of matrix T. - * \return Dimension of matrix T. */ -unsigned int Flipper_getDimT( Flipper* _THIS ); - - -END_NAMESPACE_QPOASES - - -#endif /* QPOASES_FLIPPER_H */ - - -/* - * end of file - */ diff --git a/third_party/acados/include/qpOASES_e/Indexlist.h b/third_party/acados/include/qpOASES_e/Indexlist.h deleted file mode 100644 index 02d259d63d..0000000000 --- a/third_party/acados/include/qpOASES_e/Indexlist.h +++ /dev/null @@ -1,221 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/Indexlist.h - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - * - * Declaration of the Indexlist class designed to manage index lists of - * constraints and bounds within a SubjectTo object. - */ - - -#ifndef QPOASES_INDEXLIST_H -#define QPOASES_INDEXLIST_H - - -#include - - -BEGIN_NAMESPACE_QPOASES - - -/** - * \brief Stores and manages index lists. - * - * This class manages index lists of active/inactive bounds/constraints. - * - * \author Hans Joachim Ferreau - * \version 3.1embedded - * \date 2007-2015 - */ -typedef struct -{ - int *number; /**< Array to store numbers of constraints or bounds. */ - int *iSort; /**< Index list to sort vector \a number */ - - int length; /**< Length of index list. */ - int first; /**< Physical index of first element. */ - int last; /**< Physical index of last element. */ - int lastusedindex; /**< Physical index of last entry in index list. */ - int physicallength; /**< Physical length of index list. */ -} Indexlist; - -int Indexlist_calculateMemorySize( int n); - -char *Indexlist_assignMemory(int n, Indexlist **mem, void *raw_memory); - -Indexlist *Indexlist_createMemory( int n ); - -/** Constructor which takes the desired physical length of the index list. */ -void IndexlistCON( Indexlist* _THIS, - int n /**< Physical length of index list. */ - ); - -/** Copies all members from given rhs object. - * \return SUCCESSFUL_RETURN */ -void IndexlistCPY( Indexlist* FROM, - Indexlist* TO - ); - -/** Initialises index list of desired physical length. - * \return SUCCESSFUL_RETURN \n - RET_INVALID_ARGUMENTS */ -returnValue Indexlist_init( Indexlist* _THIS, - int n /**< Physical length of index list. */ - ); - -/** Creates an array of all numbers within the index set in correct order. - * \return SUCCESSFUL_RETURN \n - RET_INDEXLIST_CORRUPTED */ -returnValue Indexlist_getNumberArray( Indexlist* _THIS, - int** const numberarray /**< Output: Array of numbers (NULL on error). */ - ); - -/** Creates an array of all numbers within the index set in correct order. - * \return SUCCESSFUL_RETURN \n - RET_INDEXLIST_CORRUPTED */ -returnValue Indexlist_getISortArray( Indexlist* _THIS, - int** const iSortArray /**< Output: iSort Array. */ - ); - - -/** Determines the index within the index list at which a given number is stored. - * \return >= 0: Index of given number. \n - -1: Number not found. */ -int Indexlist_getIndex( Indexlist* _THIS, - int givennumber /**< Number whose index shall be determined. */ - ); - -/** Returns the number stored at a given physical index. - * \return >= 0: Number stored at given physical index. \n - -RET_INDEXLIST_OUTOFBOUNDS */ -static inline int Indexlist_getNumber( Indexlist* _THIS, - int physicalindex /**< Physical index of the number to be returned. */ - ); - - -/** Returns the current length of the index list. - * \return Current length of the index list. */ -static inline int Indexlist_getLength( Indexlist* _THIS - ); - -/** Returns last number within the index list. - * \return Last number within the index list. */ -static inline int Indexlist_getLastNumber( Indexlist* _THIS - ); - - -/** Adds number to index list. - * \return SUCCESSFUL_RETURN \n - RET_INDEXLIST_MUST_BE_REORDERD \n - RET_INDEXLIST_EXCEEDS_MAX_LENGTH */ -returnValue Indexlist_addNumber( Indexlist* _THIS, - int addnumber /**< Number to be added. */ - ); - -/** Removes number from index list. - * \return SUCCESSFUL_RETURN */ -returnValue Indexlist_removeNumber( Indexlist* _THIS, - int removenumber /**< Number to be removed. */ - ); - -/** Swaps two numbers within index list. - * \return SUCCESSFUL_RETURN */ -returnValue Indexlist_swapNumbers( Indexlist* _THIS, - int number1, /**< First number for swapping. */ - int number2 /**< Second number for swapping. */ - ); - -/** Determines if a given number is contained in the index set. - * \return BT_TRUE iff number is contain in the index set */ -static inline BooleanType Indexlist_isMember( Indexlist* _THIS, - int _number /**< Number to be tested for membership. */ - ); - - -/** Find first index j between -1 and length in sorted list of indices - * iSort such that numbers[iSort[j]] <= i < numbers[iSort[j+1]]. Uses - * bisection. - * \return j. */ -int Indexlist_findInsert( Indexlist* _THIS, - int i - ); - - - -/* - * g e t N u m b e r - */ -static inline int Indexlist_getNumber( Indexlist* _THIS, int physicalindex ) -{ - /* consistency check */ - if ( ( physicalindex < 0 ) || ( physicalindex > _THIS->length ) ) - return -RET_INDEXLIST_OUTOFBOUNDS; - - return _THIS->number[physicalindex]; -} - - -/* - * g e t L e n g t h - */ -static inline int Indexlist_getLength( Indexlist* _THIS ) -{ - return _THIS->length; -} - - -/* - * g e t L a s t N u m b e r - */ -static inline int Indexlist_getLastNumber( Indexlist* _THIS ) -{ - return _THIS->number[_THIS->length-1]; -} - - -/* - * g e t L a s t N u m b e r - */ -static inline BooleanType Indexlist_isMember( Indexlist* _THIS, int _number ) -{ - if ( Indexlist_getIndex( _THIS,_number ) >= 0 ) - return BT_TRUE; - else - return BT_FALSE; -} - - -END_NAMESPACE_QPOASES - - -#endif /* QPOASES_INDEXLIST_H */ - - -/* - * end of file - */ diff --git a/third_party/acados/include/qpOASES_e/Matrices.h b/third_party/acados/include/qpOASES_e/Matrices.h deleted file mode 100644 index e2a46b3a9d..0000000000 --- a/third_party/acados/include/qpOASES_e/Matrices.h +++ /dev/null @@ -1,287 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/Matrices.h - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2009-2015 - * - * Various matrix classes: Abstract base matrix class, dense and sparse matrices, - * including symmetry exploiting specializations. - */ - - - -#ifndef QPOASES_MATRICES_H -#define QPOASES_MATRICES_H - -#ifdef __USE_SINGLE_PRECISION__ - - // single precision - #define GEMM sgemm_ - #define GEMV sgemv_ -// #define SYR ssyr_ -// #define SYR2 ssyr2_ - #define POTRF spotrf_ - -#else - - // double precision - #define GEMM dgemm_ - #define GEMV dgemv_ -// #define SYR dsyr_ -// #define SYR2 dsyr2_ - #define POTRF dpotrf_ - -#endif /* __USE_SINGLE_PRECISION__ */ - - -#ifdef EXTERNAL_BLAS - // double precision - void dgemm_(char *ta, char *tb, int *m, int *n, int *k, double *alpha, double *A, int *lda, double *B, int ldb, double *beta, double *C, int *ldc); - void dgemv_(char *ta, int *m, int *n, double *alpha, double *A, int *lda, double *x, int *incx, double *beta, double *y, int *incy); - void dpotrf_(char *uplo, int *m, double *A, int *lda, int *info); - // single precision - void sgemm_(char *ta, char *tb, int *m, int *n, int *k, float *alpha, float *A, int *lda, float *B, int ldb, float *beta, float *C, int *ldc); - void sgemv_(char *ta, int *m, int *n, float *alpha, float *A, int *lda, float *x, int *incx, float *beta, float *y, int *incy); - void spotrf_(char *uplo, int *m, float *A, int *lda, int *info); -#else - /** Performs one of the matrix-matrix operation in double precision. */ - void dgemm_ ( const char*, const char*, const unsigned long*, const unsigned long*, const unsigned long*, - const double*, const double*, const unsigned long*, const double*, const unsigned long*, - const double*, double*, const unsigned long* ); - /** Performs one of the matrix-matrix operation in single precision. */ - void sgemm_ ( const char*, const char*, const unsigned long*, const unsigned long*, const unsigned long*, - const float*, const float*, const unsigned long*, const float*, const unsigned long*, - const float*, float*, const unsigned long* ); - - /** Calculates the Cholesky factorization of a real symmetric positive definite matrix in double precision. */ - void dpotrf_ ( const char *, const unsigned long *, double *, const unsigned long *, long * ); - /** Calculates the Cholesky factorization of a real symmetric positive definite matrix in single precision. */ - void spotrf_ ( const char *, const unsigned long *, float *, const unsigned long *, long * ); - -#endif - - /** Performs a symmetric rank 1 operation in double precision. */ -// void dsyr_ ( const char *, const unsigned long *, const double *, const double *, -// const unsigned long *, double *, const unsigned long *); - /** Performs a symmetric rank 1 operation in single precision. */ -// void ssyr_ ( const char *, const unsigned long *, const float *, const float *, -// const unsigned long *, float *, const unsigned long *); - - /** Performs a symmetric rank 2 operation in double precision. */ -// void dsyr2_ ( const char *, const unsigned long *, const double *, const double *, -// const unsigned long *, const double *, const unsigned long *, double *, const unsigned long *); - /** Performs a symmetric rank 2 operation in single precision. */ -// void ssyr2_ ( const char *, const unsigned long *, const float *, const float *, -// const unsigned long *, const float *, const unsigned long *, float *, const unsigned long *); - - -#include - - -BEGIN_NAMESPACE_QPOASES - - -/** - * \brief Interfaces matrix-vector operations tailored to general dense matrices. - * - * Dense matrix class (row major format). - * - * \author Andreas Potschka, Christian Kirches, Hans Joachim Ferreau - * \version 3.1embedded - * \date 2011-2015 - */ -typedef struct -{ - real_t *val; /**< Vector of entries. */ - int nRows; /**< Number of rows. */ - int nCols; /**< Number of columns. */ - int leaDim; /**< Leading dimension. */ -} DenseMatrix; - -int DenseMatrix_calculateMemorySize( int m, int n ); - -char *DenseMatrix_assignMemory( int m, int n, DenseMatrix **mem, void *raw_memory ); - -DenseMatrix *DenseMatrix_createMemory( int m, int n ); - -/** Constructor from vector of values. - * Caution: Data pointer must be valid throughout lifetime - */ -void DenseMatrixCON( DenseMatrix* _THIS, - int m, /**< Number of rows. */ - int n, /**< Number of columns. */ - int lD, /**< Leading dimension. */ - real_t *v /**< Values. */ - ); - -void DenseMatrixCPY( DenseMatrix* FROM, - DenseMatrix* TO - ); - - -/** Frees all internal memory. */ -void DenseMatrix_free( DenseMatrix* _THIS ); - -/** Constructor from vector of values. - * Caution: Data pointer must be valid throughout lifetime - */ -returnValue DenseMatrix_init( DenseMatrix* _THIS, - int m, /**< Number of rows. */ - int n, /**< Number of columns. */ - int lD, /**< Leading dimension. */ - real_t *v /**< Values. */ - ); - - -/** Returns i-th diagonal entry. - * \return i-th diagonal entry */ -real_t DenseMatrix_diag( DenseMatrix* _THIS, - int i /**< Index. */ - ); - -/** Checks whether matrix is square and diagonal. - * \return BT_TRUE iff matrix is square and diagonal; \n - * BT_FALSE otherwise. */ -BooleanType DenseMatrix_isDiag( DenseMatrix* _THIS ); - -/** Get the N-norm of the matrix - * \return N-norm of the matrix - */ -real_t DenseMatrix_getNorm( DenseMatrix* _THIS, - int type /**< Norm type, 1: one-norm, 2: Euclidean norm. */ - ); - -/** Get the N-norm of a row - * \return N-norm of row \a rNum - */ -real_t DenseMatrix_getRowNorm( DenseMatrix* _THIS, - int rNum, /**< Row number. */ - int type /**< Norm type, 1: one-norm, 2: Euclidean norm. */ - ); - -/** Retrieve indexed entries of matrix row multiplied by alpha. - * \return SUCCESSFUL_RETURN */ -returnValue DenseMatrix_getRow( DenseMatrix* _THIS, - int rNum, /**< Row number. */ - const Indexlist* const icols, /**< Index list specifying columns. */ - real_t alpha, /**< Scalar factor. */ - real_t *row /**< Output row vector. */ - ); - -/** Retrieve indexed entries of matrix column multiplied by alpha. - * \return SUCCESSFUL_RETURN */ - returnValue DenseMatrix_getCol( DenseMatrix* _THIS, - int cNum, /**< Column number. */ - const Indexlist* const irows, /**< Index list specifying rows. */ - real_t alpha, /**< Scalar factor. */ - real_t *col /**< Output column vector. */ - ); - -/** Evaluate Y=alpha*A*X + beta*Y. - * \return SUCCESSFUL_RETURN. */ -returnValue DenseMatrix_times( DenseMatrix* _THIS, - int xN, /**< Number of vectors to multiply. */ - real_t alpha, /**< Scalar factor for matrix vector product. */ - const real_t *x, /**< Input vector to be multiplied. */ - int xLD, /**< Leading dimension of input x. */ - real_t beta, /**< Scalar factor for y. */ - real_t *y, /**< Output vector of results. */ - int yLD /**< Leading dimension of output y. */ - ); - -/** Evaluate Y=alpha*A'*X + beta*Y. - * \return SUCCESSFUL_RETURN. */ -returnValue DenseMatrix_transTimes( DenseMatrix* _THIS, - int xN, /**< Number of vectors to multiply. */ - real_t alpha, /**< Scalar factor for matrix vector product. */ - const real_t *x, /**< Input vector to be multiplied. */ - int xLD, /**< Leading dimension of input x. */ - real_t beta, /**< Scalar factor for y. */ - real_t *y, /**< Output vector of results. */ - int yLD /**< Leading dimension of output y. */ - ); - -/** Evaluate matrix vector product with submatrix given by Indexlist. - * \return SUCCESSFUL_RETURN */ - returnValue DenseMatrix_subTimes( DenseMatrix* _THIS, - const Indexlist* const irows, /**< Index list specifying rows. */ - const Indexlist* const icols, /**< Index list specifying columns. */ - int xN, /**< Number of vectors to multiply. */ - real_t alpha, /**< Scalar factor for matrix vector product. */ - const real_t *x, /**< Input vector to be multiplied. */ - int xLD, /**< Leading dimension of input x. */ - real_t beta, /**< Scalar factor for y. */ - real_t *y, /**< Output vector of results. */ - int yLD, /**< Leading dimension of output y. */ - BooleanType yCompr /**< Compressed storage for y. */ - ); - -/** Evaluate matrix transpose vector product. - * \return SUCCESSFUL_RETURN */ -returnValue DenseMatrix_subTransTimes( DenseMatrix* _THIS, - const Indexlist* const irows, /**< Index list specifying rows. */ - const Indexlist* const icols, /**< Index list specifying columns. */ - int xN, /**< Number of vectors to multiply. */ - real_t alpha, /**< Scalar factor for matrix vector product. */ - const real_t *x, /**< Input vector to be multiplied. */ - int xLD, /**< Leading dimension of input x. */ - real_t beta, /**< Scalar factor for y. */ - real_t *y, /**< Output vector of results. */ - int yLD /**< Leading dimension of output y. */ - ); - -/** Adds given offset to diagonal of matrix. - * \return SUCCESSFUL_RETURN \n - RET_NO_DIAGONAL_AVAILABLE */ -returnValue DenseMatrix_addToDiag( DenseMatrix* _THIS, - real_t alpha /**< Diagonal offset. */ - ); - -/** Prints matrix to screen. - * \return SUCCESSFUL_RETURN */ -returnValue DenseMatrix_print( DenseMatrix* _THIS - ); - -static inline real_t* DenseMatrix_getVal( DenseMatrix* _THIS ) { return _THIS->val; } - -/** Compute bilinear form y = x'*H*x using submatrix given by index list. - * \return SUCCESSFUL_RETURN */ -returnValue DenseMatrix_bilinear( DenseMatrix* _THIS, - const Indexlist* const icols, /**< Index list specifying columns of x. */ - int xN, /**< Number of vectors to multiply. */ - const real_t *x, /**< Input vector to be multiplied (uncompressed). */ - int xLD, /**< Leading dimension of input x. */ - real_t *y, /**< Output vector of results (compressed). */ - int yLD /**< Leading dimension of output y. */ - ); - - - -END_NAMESPACE_QPOASES - - -#endif /* QPOASES_MATRICES_H */ diff --git a/third_party/acados/include/qpOASES_e/MessageHandling.h b/third_party/acados/include/qpOASES_e/MessageHandling.h deleted file mode 100644 index fe5524948a..0000000000 --- a/third_party/acados/include/qpOASES_e/MessageHandling.h +++ /dev/null @@ -1,544 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/MessageHandling.h - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches (thanks to Leonard Wirsching) - * \version 3.1embedded - * \date 2007-2015 - * - * Declaration of the MessageHandling class including global return values. - */ - - -#ifndef QPOASES_MESSAGEHANDLING_H -#define QPOASES_MESSAGEHANDLING_H - - -#include -#include -#include -#include - -#include - - -BEGIN_NAMESPACE_QPOASES - - -/** Default file to display messages. */ -#define stdFile stderr - - -/** - * \brief Defines all symbols for global return values. - * - * The enumeration returnValueType defines all symbols for global return values. - * Important: All return values are assumed to be nonnegative! - * - * \author Hans Joachim Ferreau - */ -typedef enum -{ -TERMINAL_LIST_ELEMENT = -1, /**< Terminal list element, internal usage only! */ -/* miscellaneous */ -SUCCESSFUL_RETURN = 0, /**< Successful return. */ -RET_DIV_BY_ZERO, /**< Division by zero. */ -RET_INDEX_OUT_OF_BOUNDS, /**< Index out of bounds. */ -RET_INVALID_ARGUMENTS, /**< At least one of the arguments is invalid. */ -RET_ERROR_UNDEFINED, /**< Error number undefined. */ -RET_WARNING_UNDEFINED, /**< Warning number undefined. */ -RET_INFO_UNDEFINED, /**< Info number undefined. */ -RET_EWI_UNDEFINED, /**< Error/warning/info number undefined. */ -RET_AVAILABLE_WITH_LINUX_ONLY, /**< This function is available under Linux only. */ -RET_UNKNOWN_BUG, /**< The error occurred is not yet known. */ -RET_PRINTLEVEL_CHANGED, /**< Print level changed. (10) */ -RET_NOT_YET_IMPLEMENTED, /**< Requested function is not yet implemented in this version of qpOASES. */ -/* Indexlist */ -RET_INDEXLIST_MUST_BE_REORDERD, /**< Index list has to be reordered. */ -RET_INDEXLIST_EXCEEDS_MAX_LENGTH, /**< Index list exceeds its maximal physical length. */ -RET_INDEXLIST_CORRUPTED, /**< Index list corrupted. */ -RET_INDEXLIST_OUTOFBOUNDS, /**< Physical index is out of bounds. */ -RET_INDEXLIST_ADD_FAILED, /**< Adding indices from another index set failed. */ -RET_INDEXLIST_INTERSECT_FAILED, /**< Intersection with another index set failed. */ -/* SubjectTo / Bounds / Constraints */ -RET_INDEX_ALREADY_OF_DESIRED_STATUS, /**< Index is already of desired status. (18) */ -RET_ADDINDEX_FAILED, /**< Adding index to index set failed. */ -RET_REMOVEINDEX_FAILED, /**< Removing index from index set failed. (20) */ -RET_SWAPINDEX_FAILED, /**< Cannot swap between different indexsets. */ -RET_NOTHING_TO_DO, /**< Nothing to do. */ -RET_SETUP_BOUND_FAILED, /**< Setting up bound index failed. */ -RET_SETUP_CONSTRAINT_FAILED, /**< Setting up constraint index failed. */ -RET_MOVING_BOUND_FAILED, /**< Moving bound between index sets failed. */ -RET_MOVING_CONSTRAINT_FAILED, /**< Moving constraint between index sets failed. */ -RET_SHIFTING_FAILED, /**< Shifting of bounds/constraints failed. */ -RET_ROTATING_FAILED, /**< Rotating of bounds/constraints failed. */ -/* QProblem */ -RET_QPOBJECT_NOT_SETUP, /**< The QP object has not been setup correctly, use another constructor. */ -RET_QP_ALREADY_INITIALISED, /**< QProblem has already been initialised. (30) */ -RET_NO_INIT_WITH_STANDARD_SOLVER, /**< Initialisation via extern QP solver is not yet implemented. */ -RET_RESET_FAILED, /**< Reset failed. */ -RET_INIT_FAILED, /**< Initialisation failed. */ -RET_INIT_FAILED_TQ, /**< Initialisation failed due to TQ factorisation. */ -RET_INIT_FAILED_CHOLESKY, /**< Initialisation failed due to Cholesky decomposition. */ -RET_INIT_FAILED_HOTSTART, /**< Initialisation failed! QP could not be solved! */ -RET_INIT_FAILED_INFEASIBILITY, /**< Initial QP could not be solved due to infeasibility! */ -RET_INIT_FAILED_UNBOUNDEDNESS, /**< Initial QP could not be solved due to unboundedness! */ -RET_INIT_FAILED_REGULARISATION, /**< Initialisation failed as Hessian matrix could not be regularised. */ -RET_INIT_SUCCESSFUL, /**< Initialisation done. (40) */ -RET_OBTAINING_WORKINGSET_FAILED, /**< Failed to obtain working set for auxiliary QP. */ -RET_SETUP_WORKINGSET_FAILED, /**< Failed to setup working set for auxiliary QP. */ -RET_SETUP_AUXILIARYQP_FAILED, /**< Failed to setup auxiliary QP for initialised homotopy. */ -RET_NO_CHOLESKY_WITH_INITIAL_GUESS, /**< Externally computed Cholesky factor cannot be combined with an initial guess. */ -RET_NO_EXTERN_SOLVER, /**< No extern QP solver available. */ -RET_QP_UNBOUNDED, /**< QP is unbounded. */ -RET_QP_INFEASIBLE, /**< QP is infeasible. */ -RET_QP_NOT_SOLVED, /**< Problems occurred while solving QP with standard solver. */ -RET_QP_SOLVED, /**< QP successfully solved. */ -RET_UNABLE_TO_SOLVE_QP, /**< Problems occurred while solving QP. (50) */ -RET_INITIALISATION_STARTED, /**< Starting problem initialisation... */ -RET_HOTSTART_FAILED, /**< Unable to perform homotopy due to internal error. */ -RET_HOTSTART_FAILED_TO_INIT, /**< Unable to initialise problem. */ -RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED, /**< Unable to perform homotopy as previous QP is not solved. */ -RET_ITERATION_STARTED, /**< Iteration... */ -RET_SHIFT_DETERMINATION_FAILED, /**< Determination of shift of the QP data failed. */ -RET_STEPDIRECTION_DETERMINATION_FAILED, /**< Determination of step direction failed. */ -RET_STEPLENGTH_DETERMINATION_FAILED, /**< Determination of step direction failed. */ -RET_OPTIMAL_SOLUTION_FOUND, /**< Optimal solution of neighbouring QP found. */ -RET_HOMOTOPY_STEP_FAILED, /**< Unable to perform homotopy step. (60) */ -RET_HOTSTART_STOPPED_INFEASIBILITY, /**< Premature homotopy termination because QP is infeasible. */ -RET_HOTSTART_STOPPED_UNBOUNDEDNESS, /**< Premature homotopy termination because QP is unbounded. */ -RET_WORKINGSET_UPDATE_FAILED, /**< Unable to update working sets according to initial guesses. */ -RET_MAX_NWSR_REACHED, /**< Maximum number of working set recalculations performed. */ -RET_CONSTRAINTS_NOT_SPECIFIED, /**< Problem does comprise constraints! You also have to specify new constraints' bounds. */ -RET_INVALID_FACTORISATION_FLAG, /**< Invalid factorisation flag. */ -RET_UNABLE_TO_SAVE_QPDATA, /**< Unable to save QP data. */ -RET_STEPDIRECTION_FAILED_TQ, /**< Abnormal termination due to TQ factorisation. */ -RET_STEPDIRECTION_FAILED_CHOLESKY, /**< Abnormal termination due to Cholesky factorisation. */ -RET_CYCLING_DETECTED, /**< Cycling detected. (70) */ -RET_CYCLING_NOT_RESOLVED, /**< Cycling cannot be resolved, QP probably infeasible. */ -RET_CYCLING_RESOLVED, /**< Cycling probably resolved. */ -RET_STEPSIZE, /**< For displaying performed stepsize. */ -RET_STEPSIZE_NONPOSITIVE, /**< For displaying non-positive stepsize. */ -RET_SETUPSUBJECTTOTYPE_FAILED, /**< Setup of SubjectToTypes failed. */ -RET_ADDCONSTRAINT_FAILED, /**< Addition of constraint to working set failed. */ -RET_ADDCONSTRAINT_FAILED_INFEASIBILITY, /**< Addition of constraint to working set failed (due to QP infeasibility). */ -RET_ADDBOUND_FAILED, /**< Addition of bound to working set failed. */ -RET_ADDBOUND_FAILED_INFEASIBILITY, /**< Addition of bound to working set failed (due to QP infeasibility). */ -RET_REMOVECONSTRAINT_FAILED, /**< Removal of constraint from working set failed. (80) */ -RET_REMOVEBOUND_FAILED, /**< Removal of bound from working set failed. */ -RET_REMOVE_FROM_ACTIVESET, /**< Removing from active set... */ -RET_ADD_TO_ACTIVESET, /**< Adding to active set... */ -RET_REMOVE_FROM_ACTIVESET_FAILED, /**< Removing from active set failed. */ -RET_ADD_TO_ACTIVESET_FAILED, /**< Adding to active set failed. */ -RET_CONSTRAINT_ALREADY_ACTIVE, /**< Constraint is already active. */ -RET_ALL_CONSTRAINTS_ACTIVE, /**< All constraints are active, no further constraint can be added. */ -RET_LINEARLY_DEPENDENT, /**< New bound/constraint is linearly dependent. */ -RET_LINEARLY_INDEPENDENT, /**< New bound/constraint is linearly independent. */ -RET_LI_RESOLVED, /**< Linear independence of active constraint matrix successfully resolved. (90) */ -RET_ENSURELI_FAILED, /**< Failed to ensure linear independence of active constraint matrix. */ -RET_ENSURELI_FAILED_TQ, /**< Abnormal termination due to TQ factorisation. */ -RET_ENSURELI_FAILED_NOINDEX, /**< QP is infeasible. */ -RET_ENSURELI_FAILED_CYCLING, /**< QP is infeasible. */ -RET_BOUND_ALREADY_ACTIVE, /**< Bound is already active. */ -RET_ALL_BOUNDS_ACTIVE, /**< All bounds are active, no further bound can be added. */ -RET_CONSTRAINT_NOT_ACTIVE, /**< Constraint is not active. */ -RET_BOUND_NOT_ACTIVE, /**< Bound is not active. */ -RET_HESSIAN_NOT_SPD, /**< Projected Hessian matrix not positive definite. */ -RET_HESSIAN_INDEFINITE, /**< Hessian matrix is indefinite. (100) */ -RET_MATRIX_SHIFT_FAILED, /**< Unable to update matrices or to transform vectors. */ -RET_MATRIX_FACTORISATION_FAILED, /**< Unable to calculate new matrix factorisations. */ -RET_PRINT_ITERATION_FAILED, /**< Unable to print information on current iteration. */ -RET_NO_GLOBAL_MESSAGE_OUTPUTFILE, /**< No global message output file initialised. */ -RET_DISABLECONSTRAINTS_FAILED, /**< Unable to disbable constraints. */ -RET_ENABLECONSTRAINTS_FAILED, /**< Unable to enbable constraints. */ -RET_ALREADY_ENABLED, /**< Bound or constraint is already enabled. */ -RET_ALREADY_DISABLED, /**< Bound or constraint is already disabled. */ -RET_NO_HESSIAN_SPECIFIED, /**< No Hessian matrix has been specified. */ -RET_USING_REGULARISATION, /**< Using regularisation as Hessian matrix is not positive definite. (110) */ -RET_EPS_MUST_BE_POSITVE, /**< Eps for regularisation must be sufficiently positive. */ -RET_REGSTEPS_MUST_BE_POSITVE, /**< Maximum number of regularisation steps must be non-negative. */ -RET_HESSIAN_ALREADY_REGULARISED, /**< Hessian has been already regularised. */ -RET_CANNOT_REGULARISE_IDENTITY, /**< Identity Hessian matrix cannot be regularised. */ -RET_CANNOT_REGULARISE_SPARSE, /**< Sparse matrix cannot be regularised as diagonal entry is missing. */ -RET_NO_REGSTEP_NWSR, /**< No additional regularisation step could be performed due to limits. */ -RET_FEWER_REGSTEPS_NWSR, /**< Fewer additional regularisation steps have been performed due to limits. */ -RET_CHOLESKY_OF_ZERO_HESSIAN, /**< Cholesky decomposition of (unregularised) zero Hessian matrix. */ -RET_ZERO_HESSIAN_ASSUMED, /**< Zero Hessian matrix assumed as null pointer passed without specifying hessianType. */ -RET_CONSTRAINTS_ARE_NOT_SCALED, /**< (no longer in use) (120) */ -RET_INITIAL_BOUNDS_STATUS_NYI, /**< (no longer in use) */ -RET_ERROR_IN_CONSTRAINTPRODUCT, /**< Error in user-defined constraint product function. */ -RET_FIX_BOUNDS_FOR_LP, /**< All initial bounds must be fixed when solving an (unregularised) LP. */ -RET_USE_REGULARISATION_FOR_LP, /**< Set options.enableRegularisation=BT_TRUE for solving LPs. */ -/* SQProblem */ -RET_UPDATEMATRICES_FAILED, /**< Unable to update QP matrices. */ -RET_UPDATEMATRICES_FAILED_AS_QP_NOT_SOLVED, /**< Unable to update matrices as previous QP is not solved. */ -/* Utils */ -RET_UNABLE_TO_OPEN_FILE, /**< Unable to open file. */ -RET_UNABLE_TO_WRITE_FILE, /**< Unable to write into file. */ -RET_UNABLE_TO_READ_FILE, /**< Unable to read from file. */ -RET_FILEDATA_INCONSISTENT, /**< File contains inconsistent data. (130) */ -/* Options */ -RET_OPTIONS_ADJUSTED, /**< Options needed to be adjusted for consistency reasons. */ -/* SolutionAnalysis */ -RET_UNABLE_TO_ANALYSE_QPROBLEM, /**< Unable to analyse (S)QProblem(B) object. */ -/* Benchmark */ -RET_NWSR_SET_TO_ONE, /**< Maximum number of working set changes was set to 1. */ -RET_UNABLE_TO_READ_BENCHMARK, /**< Unable to read benchmark data. */ -RET_BENCHMARK_ABORTED, /**< Benchmark aborted. */ -RET_INITIAL_QP_SOLVED, /**< Initial QP solved. */ -RET_QP_SOLUTION_STARTED, /**< Solving QP... */ -RET_BENCHMARK_SUCCESSFUL, /**< Benchmark terminated successfully. */ -/* Sparse matrices */ -RET_NO_DIAGONAL_AVAILABLE, /**< Sparse matrix does not have entries on full diagonal. */ -RET_DIAGONAL_NOT_INITIALISED, /**< Diagonal data of sparse matrix has not been initialised. (140) */ -/* Dropping of infeasible constraints */ -RET_ENSURELI_DROPPED, /**< Linear independence resolved by dropping blocking constraint. */ -/* Simple exitflags */ -RET_SIMPLE_STATUS_P1, /**< QP problem could not be solved within given number of iterations. */ -RET_SIMPLE_STATUS_P0, /**< QP problem solved. */ -RET_SIMPLE_STATUS_M1, /**< QP problem could not be solved due to an internal error. */ -RET_SIMPLE_STATUS_M2, /**< QP problem is infeasible (and thus could not be solved). */ -RET_SIMPLE_STATUS_M3 /**< QP problem is unbounded (and thus could not be solved). (146) */ -} returnValue; - - -/** - * \brief Data structure for entries in global message list. - * - * Data structure for entries in global message list. - * - * \author Hans Joachim Ferreau - * \version 3.1embedded - * \date 2007-2015 - */ -typedef struct -{ - returnValue key; /**< Global return value. */ - const char* data; /**< Corresponding message. */ - VisibilityStatus globalVisibilityStatus; /**< Determines if message can be printed. - * If this value is set to VS_HIDDEN, no message is printed! */ -} ReturnValueList; - - - -/** - * \brief Handles all kind of error messages, warnings and other information. - * - * This class handles all kinds of messages (errors, warnings, infos) initiated - * by qpOASES modules and stores the corresponding global preferences. - * - * \author Hans Joachim Ferreau (thanks to Leonard Wirsching) - * \version 3.1embedded - * \date 2007-2015 - */ -typedef struct -{ - VisibilityStatus errorVisibility; /**< Error messages visible? */ - VisibilityStatus warningVisibility; /**< Warning messages visible? */ - VisibilityStatus infoVisibility; /**< Info messages visible? */ - - FILE* outputFile; /**< Output file for messages. */ - - int errorCount; /**< Counts number of errors (for nicer output only). */ -} MessageHandling; - - - -/** Constructor which takes the desired output file and desired visibility states. */ -void MessageHandlingCON( MessageHandling* _THIS, - FILE* _outputFile, /**< Output file. */ - VisibilityStatus _errorVisibility, /**< Visibility status for error messages. */ - VisibilityStatus _warningVisibility,/**< Visibility status for warning messages. */ - VisibilityStatus _infoVisibility /**< Visibility status for info messages. */ - ); - -void MessageHandlingCPY( MessageHandling* FROM, - MessageHandling* TO - ); - - -/** Prints an error message(a simplified macro THROWERROR is also provided). \n - * Errors are definied as abnormal events which cause an immediate termination of the current (sub) function. - * Errors of a sub function should be commented by the calling function by means of a warning message - * (if this error does not cause an error of the calling function, either)! - * \return Error number returned by sub function call - */ -returnValue MessageHandling_throwError( MessageHandling* _THIS, - returnValue Enumber, /**< Error number returned by sub function call. */ - const char* additionaltext, /**< Additional error text (0, if none). */ - const char* functionname, /**< Name of function which caused the error. */ - const char* filename, /**< Name of file which caused the error. */ - const unsigned long linenumber, /**< Number of line which caused the error.incompatible binary file */ - VisibilityStatus localVisibilityStatus /**< Determines (locally) if error message can be printed to stderr. - * If GLOBAL visibility status of the message is set to VS_HIDDEN, - * no message is printed, anyway! */ - ); - -/** Prints a warning message (a simplified macro THROWWARNING is also provided). - * Warnings are definied as abnormal events which does NOT cause an immediate termination of the current (sub) function. - * \return Warning number returned by sub function call - */ -returnValue MessageHandling_throwWarning( MessageHandling* _THIS, - returnValue Wnumber, /**< Warning number returned by sub function call. */ - const char* additionaltext, /**< Additional warning text (0, if none). */ - const char* functionname, /**< Name of function which caused the warning. */ - const char* filename, /**< Name of file which caused the warning. */ - const unsigned long linenumber, /**< Number of line which caused the warning. */ - VisibilityStatus localVisibilityStatus /**< Determines (locally) if warning message can be printed to stderr. - * If GLOBAL visibility status of the message is set to VS_HIDDEN, - * no message is printed, anyway! */ - ); - -/** Prints a info message (a simplified macro THROWINFO is also provided). - * \return Info number returned by sub function call - */ -returnValue MessageHandling_throwInfo( MessageHandling* _THIS, - returnValue Inumber, /**< Info number returned by sub function call. */ - const char* additionaltext, /**< Additional warning text (0, if none). */ - const char* functionname, /**< Name of function which submitted the info. */ - const char* filename, /**< Name of file which submitted the info. */ - const unsigned long linenumber, /**< Number of line which submitted the info. */ - VisibilityStatus localVisibilityStatus /**< Determines (locally) if info message can be printed to stderr. - * If GLOBAL visibility status of the message is set to VS_HIDDEN, - * no message is printed, anyway! */ - ); - - -/** Resets all preferences to default values. - * \return SUCCESSFUL_RETURN */ -returnValue MessageHandling_reset( MessageHandling* _THIS ); - - -/** Prints a complete list of all messages to output file. - * \return SUCCESSFUL_RETURN */ -returnValue MessageHandling_listAllMessages( MessageHandling* _THIS ); - - -/** Returns visibility status for error messages. - * \return Visibility status for error messages. */ -static inline VisibilityStatus MessageHandling_getErrorVisibilityStatus( MessageHandling* _THIS ); - -/** Returns visibility status for warning messages. - * \return Visibility status for warning messages. */ -static inline VisibilityStatus MessageHandling_getWarningVisibilityStatus( MessageHandling* _THIS ); - -/** Returns visibility status for info messages. - * \return Visibility status for info messages. */ -static inline VisibilityStatus MessageHandling_getInfoVisibilityStatus( MessageHandling* _THIS ); - -/** Returns pointer to output file. - * \return Pointer to output file. */ -static inline FILE* MessageHandling_getOutputFile( MessageHandling* _THIS ); - -/** Returns error count value. - * \return Error count value. */ -static inline int MessageHandling_getErrorCount( MessageHandling* _THIS ); - - -/** Changes visibility status for error messages. */ -static inline void MessageHandling_setErrorVisibilityStatus( MessageHandling* _THIS, - VisibilityStatus _errorVisibility /**< New visibility status for error messages. */ - ); - -/** Changes visibility status for warning messages. */ -static inline void MessageHandling_setWarningVisibilityStatus( MessageHandling* _THIS, - VisibilityStatus _warningVisibility /**< New visibility status for warning messages. */ - ); - -/** Changes visibility status for info messages. */ -static inline void MessageHandling_setInfoVisibilityStatus( MessageHandling* _THIS, - VisibilityStatus _infoVisibility /**< New visibility status for info messages. */ - ); - -/** Changes output file for messages. */ -static inline void MessageHandling_setOutputFile( MessageHandling* _THIS, - FILE* _outputFile /**< New output file for messages. */ - ); - -/** Changes error count. - * \return SUCCESSFUL_RETURN \n - * RET_INVALID_ARGUMENT */ -static inline returnValue MessageHandling_setErrorCount( MessageHandling* _THIS, - int _errorCount /**< New error count value. */ - ); - -/** Provides message text corresponding to given \a returnValue. - * \return String containing message text. */ -const char* MessageHandling_getErrorCodeMessage( MessageHandling* _THIS, - const returnValue _returnValue - ); - - -returnValue MessageHandling_throwMessage( MessageHandling* _THIS, - returnValue RETnumber, /**< Error/warning/info number returned by sub function call. */ - const char* additionaltext, /**< Additional warning text (0, if none). */ - const char* functionname, /**< Name of function which caused the error/warning/info. */ - const char* filename, /**< Name of file which caused the error/warning/info. */ - const unsigned long linenumber, /**< Number of line which caused the error/warning/info. */ - VisibilityStatus localVisibilityStatus, /**< Determines (locally) if info message can be printed to stderr. - * If GLOBAL visibility status of the message is set to VS_HIDDEN, - * no message is printed, anyway! */ - const char* RETstring /**< Leading string of error/warning/info message. */ - ); - - -#ifndef __FILE__ - /** Ensures that __FILE__ macro is defined. */ - #define __FILE__ 0 -#endif - -#ifndef __LINE__ - /** Ensures that __LINE__ macro is defined. */ - #define __LINE__ 0 -#endif - -/** Define __FUNC__ macro providing current function for debugging. */ -/*#define __FUNC__ 0*/ -#define __FUNC__ ("(no function name provided)") -/*#define __FUNC__ __func__*/ -/*#define __FUNC__ __FUNCTION__*/ - - -/** Short version of throwError with default values, only returnValue is needed */ -#define THROWERROR(retval) ( MessageHandling_throwError( qpOASES_getGlobalMessageHandler(),(retval),0,__FUNC__,__FILE__,__LINE__,VS_VISIBLE) ) - -/** Short version of throwWarning with default values, only returnValue is needed */ -#define THROWWARNING(retval) ( MessageHandling_throwWarning( qpOASES_getGlobalMessageHandler(),(retval),0,__FUNC__,__FILE__,__LINE__,VS_VISIBLE) ) - -/** Short version of throwInfo with default values, only returnValue is needed */ -#define THROWINFO(retval) ( MessageHandling_throwInfo( qpOASES_getGlobalMessageHandler(),(retval),0,__FUNC__,__FILE__,__LINE__,VS_VISIBLE) ) - - -/** Returns a pointer to global message handler. - * \return Pointer to global message handler. - */ -MessageHandling* qpOASES_getGlobalMessageHandler( ); - - -/* - * g e t E r r o r V i s i b i l i t y S t a t u s - */ -static inline VisibilityStatus MessageHandling_getErrorVisibilityStatus( MessageHandling* _THIS ) -{ - return _THIS->errorVisibility; -} - - -/* - * g e t W a r n i n g V i s i b i l i t y S t a t u s - */ -static inline VisibilityStatus MessageHandling_getWarningVisibilityStatus( MessageHandling* _THIS ) -{ - return _THIS->warningVisibility; -} - - -/* - * g e t I n f o V i s i b i l i t y S t a t u s - */ -static inline VisibilityStatus MessageHandling_getInfoVisibilityStatus( MessageHandling* _THIS ) -{ - return _THIS->infoVisibility; -} - - -/* - * g e t O u t p u t F i l e - */ -static inline FILE* MessageHandling_getOutputFile( MessageHandling* _THIS ) -{ - return _THIS->outputFile; -} - - -/* - * g e t E r r o r C o u n t - */ -static inline int MessageHandling_getErrorCount( MessageHandling* _THIS ) -{ - return _THIS->errorCount; -} - - -/* - * s e t E r r o r V i s i b i l i t y S t a t u s - */ -static inline void MessageHandling_setErrorVisibilityStatus( MessageHandling* _THIS, VisibilityStatus _errorVisibility ) -{ - _THIS->errorVisibility = _errorVisibility; -} - - -/* - * s e t W a r n i n g V i s i b i l i t y S t a t u s - */ -static inline void MessageHandling_setWarningVisibilityStatus( MessageHandling* _THIS, VisibilityStatus _warningVisibility ) -{ - _THIS->warningVisibility = _warningVisibility; -} - - -/* - * s e t I n f o V i s i b i l i t y S t a t u s - */ -static inline void MessageHandling_setInfoVisibilityStatus( MessageHandling* _THIS, VisibilityStatus _infoVisibility ) -{ - _THIS->infoVisibility = _infoVisibility; -} - - -/* - * s e t O u t p u t F i l e - */ -static inline void MessageHandling_setOutputFile( MessageHandling* _THIS, FILE* _outputFile ) -{ - _THIS->outputFile = _outputFile; -} - - -/* - * s e t E r r o r C o u n t - */ -static inline returnValue MessageHandling_setErrorCount( MessageHandling* _THIS, int _errorCount ) -{ - if ( _errorCount >= 0 ) - { - _THIS->errorCount = _errorCount; - return SUCCESSFUL_RETURN; - } - else - return RET_INVALID_ARGUMENTS; -} - - -END_NAMESPACE_QPOASES - - -#endif /* QPOASES_MESSAGEHANDLING_H */ - - -/* - * end of file - */ diff --git a/third_party/acados/include/qpOASES_e/Options.h b/third_party/acados/include/qpOASES_e/Options.h deleted file mode 100644 index ca8086d2cc..0000000000 --- a/third_party/acados/include/qpOASES_e/Options.h +++ /dev/null @@ -1,153 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/Options.h - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - * - * Declaration of the Options class designed to manage user-specified - * options for solving a QProblem. - */ - - -#ifndef QPOASES_OPTIONS_H -#define QPOASES_OPTIONS_H - - -#include - - -BEGIN_NAMESPACE_QPOASES - - -/** - * \brief Manages all user-specified options for solving QPs. - * - * This class manages all user-specified options used for solving - * quadratic programs. - * - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - */ -typedef struct -{ - PrintLevel printLevel; /**< Print level. */ - - BooleanType enableRamping; /**< Specifies whether ramping shall be enabled or not. */ - BooleanType enableFarBounds; /**< Specifies whether far bounds shall be used or not. */ - BooleanType enableFlippingBounds; /**< Specifies whether flipping bounds shall be used or not. */ - BooleanType enableRegularisation; /**< Specifies whether Hessian matrix shall be regularised in case semi-definiteness is detected. */ - BooleanType enableFullLITests; /**< Specifies whether condition-hardened LI test shall be used or not. */ - BooleanType enableNZCTests; /**< Specifies whether nonzero curvature tests shall be used. */ - int enableDriftCorrection; /**< Specifies the frequency of drift corrections (0 = off). */ - int enableCholeskyRefactorisation; /**< Specifies the frequency of full refactorisation of proj. Hessian (otherwise updates). */ - BooleanType enableEqualities; /**< Specifies whether equalities shall be always treated as active constraints. */ - - real_t terminationTolerance; /**< Termination tolerance. */ - real_t boundTolerance; /**< Lower/upper (constraints') bound tolerance (an inequality constraint whose lower and upper bounds differ by less is regarded to be an equality constraint). */ - real_t boundRelaxation; /**< Offset for relaxing (constraints') bounds at beginning of an initial homotopy. It is also as initial value for far bounds. */ - real_t epsNum; /**< Numerator tolerance for ratio tests. */ - real_t epsDen; /**< Denominator tolerance for ratio tests. */ - real_t maxPrimalJump; /**< Maximum allowed jump in primal variables in nonzero curvature tests. */ - real_t maxDualJump; /**< Maximum allowed jump in dual variables in linear independence tests. */ - - real_t initialRamping; /**< Start value for Ramping Strategy. */ - real_t finalRamping; /**< Final value for Ramping Strategy. */ - real_t initialFarBounds; /**< Initial size of Far Bounds. */ - real_t growFarBounds; /**< Factor to grow Far Bounds. */ - SubjectToStatus initialStatusBounds; /**< Initial status of bounds at first iteration. */ - real_t epsFlipping; /**< Tolerance of squared Cholesky diagonal factor which triggers flipping bound. */ - int numRegularisationSteps; /**< Maximum number of successive regularisation steps. */ - real_t epsRegularisation; /**< Scaling factor of identity matrix used for Hessian regularisation. */ - int numRefinementSteps; /**< Maximum number of iterative refinement steps. */ - real_t epsIterRef; /**< Early termination tolerance for iterative refinement. */ - real_t epsLITests; /**< Tolerance for linear independence tests. */ - real_t epsNZCTests; /**< Tolerance for nonzero curvature tests. */ - - BooleanType enableDropInfeasibles; /**< ... */ - int dropBoundPriority; /**< ... */ - int dropEqConPriority; /**< ... */ - int dropIneqConPriority; /**< ... */ -} Options; - - -void OptionsCON( Options* _THIS - ); - -/** Copies all members from given rhs object. - * \return SUCCESSFUL_RETURN */ -void OptionsCPY( Options* FROM, - Options* TO - ); - - -/** Sets all options to default values. - * \return SUCCESSFUL_RETURN */ -returnValue Options_setToDefault( Options* _THIS - ); - -/** Sets all options to values resulting in maximum reliabilty. - * \return SUCCESSFUL_RETURN */ -returnValue Options_setToReliable( Options* _THIS - ); - -/** Sets all options to values resulting in minimum solution time. - * \return SUCCESSFUL_RETURN */ -returnValue Options_setToMPC( Options* _THIS - ); - -/** Same as setToMPC( ), for ensuring backwards compatibility. - * \return SUCCESSFUL_RETURN */ -returnValue Options_setToFast( Options* _THIS - ); - - -/** Ensures that all options have consistent values by automatically - * adjusting inconsistent ones. - * Note: This routine cannot (and does not try to) ensure that values - * are set to reasonable values that make the QP solution work! - * \return SUCCESSFUL_RETURN \n - * RET_OPTIONS_ADJUSTED */ -returnValue Options_ensureConsistency( Options* _THIS - ); - - -/** Prints values of all options. - * \return SUCCESSFUL_RETURN */ -returnValue Options_print( Options* _THIS - ); - - -END_NAMESPACE_QPOASES - - -#endif /* QPOASES_OPTIONS_H */ - - -/* - * end of file - */ diff --git a/third_party/acados/include/qpOASES_e/QProblem.h b/third_party/acados/include/qpOASES_e/QProblem.h deleted file mode 100644 index 91a4a6f396..0000000000 --- a/third_party/acados/include/qpOASES_e/QProblem.h +++ /dev/null @@ -1,2369 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/QProblem.h - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - * - * Declaration of the QProblem class which is able to use the newly - * developed online active set strategy for parametric quadratic programming. - */ - - - -#ifndef QPOASES_QPROBLEM_H -#define QPOASES_QPROBLEM_H - - -#include -#include -#include -#include -#include -#include - - -BEGIN_NAMESPACE_QPOASES - -typedef struct { - Bounds *auxiliaryBounds; - Constraints *auxiliaryConstraints; - - real_t *ub_new_far; - real_t *lb_new_far; - real_t *ubA_new_far; - real_t *lbA_new_far; - - real_t *g_new; - real_t *lb_new; - real_t *ub_new; - real_t *lbA_new; - real_t *ubA_new; - - real_t *g_new2; - real_t *lb_new2; - real_t *ub_new2; - real_t *lbA_new2; - real_t *ubA_new2; - - real_t *delta_xFX5; - real_t *delta_xFR5; - real_t *delta_yAC5; - real_t *delta_yFX5; - - real_t *Hx; - - real_t *_H; - - real_t *g_original; - real_t *lb_original; - real_t *ub_original; - real_t *lbA_original; - real_t *ubA_original; - - real_t *delta_xFR; - real_t *delta_xFX; - real_t *delta_yAC; - real_t *delta_yFX; - real_t *delta_g; - real_t *delta_lb; - real_t *delta_ub; - real_t *delta_lbA; - real_t *delta_ubA; - - real_t *gMod; - - real_t *aFR; - real_t *wZ; - - real_t *delta_g2; - real_t *delta_xFX2; - real_t *delta_xFR2; - real_t *delta_yAC2; - real_t *delta_yFX2; - real_t *nul; - real_t *Arow; - - real_t *xiC; - real_t *xiC_TMP; - real_t *xiB; - real_t *Arow2; - real_t *num; - - real_t *w; - real_t *tmp; - - real_t *delta_g3; - real_t *delta_xFX3; - real_t *delta_xFR3; - real_t *delta_yAC3; - real_t *delta_yFX3; - real_t *nul2; - - real_t *xiC2; - real_t *xiC_TMP2; - real_t *xiB2; - real_t *num2; - - real_t *Hz; - real_t *z; - real_t *ZHz; - real_t *r; - - real_t *tmp2; - real_t *Hz2; - real_t *z2; - real_t *r2; - real_t *rhs; - - real_t *delta_xFX4; - real_t *delta_xFR4; - real_t *delta_yAC4; - real_t *delta_yFX4; - real_t *nul3; - real_t *ek; - real_t *x_W; - real_t *As; - real_t *Ax_W; - - real_t *num3; - real_t *den; - real_t *delta_Ax_l; - real_t *delta_Ax_u; - real_t *delta_Ax; - real_t *delta_x; - - real_t *_A; - - real_t *grad; - real_t *AX; -} QProblem_ws; - -int QProblem_ws_calculateMemorySize( unsigned int nV, unsigned int nC ); - -char *QProblem_ws_assignMemory( unsigned int nV, unsigned int nC, QProblem_ws **mem, void *raw_memory ); - -QProblem_ws *QProblem_ws_createMemory( unsigned int nV, unsigned int nC ); - -/** - * \brief Implements the online active set strategy for QPs with general constraints. - * - * A class for setting up and solving quadratic programs. The main feature is - * the possibily to use the newly developed online active set strategy for - * parametric quadratic programming. - * - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - */ -typedef struct -{ - QProblem_ws *ws; /**< Workspace */ - Bounds *bounds; /**< Data structure for problem's bounds. */ - Constraints *constraints; /**< Data structure for problem's constraints. */ - Flipper *flipper; /**< Struct for making a temporary copy of the matrix factorisations. */ - - DenseMatrix* H; /**< Hessian matrix pointer. */ - DenseMatrix* A; /**< Constraint matrix pointer. */ - - Options options; /**< Struct containing all user-defined options for solving QPs. */ - TabularOutput tabularOutput; /**< Struct storing information for tabular output (printLevel == PL_TABULAR). */ - - real_t *g; /**< Gradient. */ - - real_t *lb; /**< Lower bound vector (on variables). */ - real_t *ub; /**< Upper bound vector (on variables). */ - real_t *lbA; /**< Lower constraints' bound vector. */ - real_t *ubA; /**< Upper constraints' bound vector. */ - - real_t *R; /**< Cholesky factor of H (i.e. H = R^T*R). */ - - real_t *T; /**< Reverse triangular matrix, A = [0 T]*Q'. */ - real_t *Q; /**< Orthonormal quadratic matrix, A = [0 T]*Q'. */ - - real_t *Ax; /**< Stores the current A*x \n - * (for increased efficiency only). */ - real_t *Ax_l; /**< Stores the current distance to lower constraints' bounds A*x-lbA \n - * (for increased efficiency only). */ - real_t *Ax_u; /**< Stores the current distance to lower constraints' bounds ubA-A*x \n - * (for increased efficiency only). */ - - real_t *x; /**< Primal solution vector. */ - real_t *y; /**< Dual solution vector. */ - - real_t *delta_xFR_TMP; /**< Temporary for determineStepDirection */ - real_t *tempA; /**< Temporary for determineStepDirection. */ - real_t *tempB; /**< Temporary for determineStepDirection. */ - real_t *ZFR_delta_xFRz; /**< Temporary for determineStepDirection. */ - real_t *delta_xFRy; /**< Temporary for determineStepDirection. */ - real_t *delta_xFRz; /**< Temporary for determineStepDirection. */ - real_t *delta_yAC_TMP; /**< Temporary for determineStepDirection. */ - - ConstraintProduct constraintProduct; /**< Pointer to user-defined constraint product function. */ - - real_t tau; /**< Last homotopy step length. */ - real_t regVal; /**< Holds the offset used to regularise Hessian matrix (zero by default). */ - - real_t ramp0; /**< Start value for Ramping Strategy. */ - real_t ramp1; /**< Final value for Ramping Strategy. */ - - QProblemStatus status; /**< Current status of the solution process. */ - HessianType hessianType; /**< Type of Hessian matrix. */ - - BooleanType haveCholesky; /**< Flag indicating whether Cholesky decomposition has already been setup. */ - BooleanType infeasible; /**< QP infeasible? */ - BooleanType unbounded; /**< QP unbounded? */ - - int rampOffset; /**< Offset index for Ramping. */ - unsigned int count; /**< Counts the number of hotstart function calls (internal usage only!). */ - - int sizeT; /**< Matrix T is stored in a (sizeT x sizeT) array. */ -} QProblem; - -int QProblem_calculateMemorySize( unsigned int nV, unsigned int nC ); - -char *QProblem_assignMemory( unsigned int nV, unsigned int nC, QProblem **mem, void *raw_memory ); - -QProblem *QProblem_createMemory( unsigned int nV, unsigned int nC ); - - -/** Constructor which takes the QP dimension and Hessian type - * information. If the Hessian is the zero (i.e. HST_ZERO) or the - * identity matrix (i.e. HST_IDENTITY), respectively, no memory - * is allocated for it and a NULL pointer can be passed for it - * to the init() functions. */ -void QProblemCON( QProblem* _THIS, - int _nV, /**< Number of variables. */ - int _nC, /**< Number of constraints. */ - HessianType _hessianType /**< Type of Hessian matrix. */ - ); - -/** Copies all members from given rhs object. - * \return SUCCESSFUL_RETURN */ -void QProblemCPY( QProblem* FROM, - QProblem* TO - ); - - -/** Clears all data structures of QProblem except for QP data. - * \return SUCCESSFUL_RETURN \n - RET_RESET_FAILED */ -returnValue QProblem_reset( QProblem* _THIS ); - - -/** Initialises a QP problem with given QP data and tries to solve it - * using at most nWSR iterations. - * - * Note: This function internally calls solveInitialQP for initialisation! - * - * \return SUCCESSFUL_RETURN \n - RET_INIT_FAILED \n - RET_INIT_FAILED_CHOLESKY \n - RET_INIT_FAILED_TQ \n - RET_INIT_FAILED_HOTSTART \n - RET_INIT_FAILED_INFEASIBILITY \n - RET_INIT_FAILED_UNBOUNDEDNESS \n - RET_MAX_NWSR_REACHED \n - RET_INVALID_ARGUMENTS */ -returnValue QProblem_initM( QProblem* _THIS, - DenseMatrix *_H, /**< Hessian matrix. */ - const real_t* const _g, /**< Gradient vector. */ - DenseMatrix *_A, /**< Constraint matrix. */ - const real_t* const _lb, /**< Lower bound vector (on variables). \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const _ub, /**< Upper bound vector (on variables). \n - If no upper bounds exist, a NULL pointer can be passed. */ - const real_t* const _lbA, /**< Lower constraints' bound vector. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const real_t* const _ubA, /**< Upper constraints' bound vector. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations when using initial homotopy. - Output: Number of performed working set recalculations. */ - real_t* const cputime /**< Input: Maximum CPU time allowed for QP initialisation. \n - Output: CPU time spent for QP initialisation (if pointer passed). */ - ); - - -/** Initialises a QP problem with given QP data and tries to solve it - * using at most nWSR iterations. - * - * Note: This function internally calls solveInitialQP for initialisation! - * - * \return SUCCESSFUL_RETURN \n - RET_INIT_FAILED \n - RET_INIT_FAILED_CHOLESKY \n - RET_INIT_FAILED_TQ \n - RET_INIT_FAILED_HOTSTART \n - RET_INIT_FAILED_INFEASIBILITY \n - RET_INIT_FAILED_UNBOUNDEDNESS \n - RET_MAX_NWSR_REACHED \n - RET_INVALID_ARGUMENTS */ -returnValue QProblem_init( QProblem* _THIS, - real_t* const _H, /**< Hessian matrix. \n - If Hessian matrix is trivial, a NULL pointer can be passed. */ - const real_t* const _g, /**< Gradient vector. */ - real_t* const _A, /**< Constraint matrix. */ - const real_t* const _lb, /**< Lower bound vector (on variables). \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const _ub, /**< Upper bound vector (on variables). \n - If no upper bounds exist, a NULL pointer can be passed. */ - const real_t* const _lbA, /**< Lower constraints' bound vector. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const real_t* const _ubA, /**< Upper constraints' bound vector. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations when using initial homotopy. - Output: Number of performed working set recalculations. */ - real_t* const cputime /**< Input: Maximum CPU time allowed for QP initialisation. \n - Output: CPU time spent for QP initialisation (if pointer passed). */ - ); - -/** Initialises a QP problem with given QP data to be read from files and tries to solve it - * using at most nWSR iterations. - * - * Note: This function internally calls solveInitialQP for initialisation! - * - * \return SUCCESSFUL_RETURN \n - RET_INIT_FAILED \n - RET_INIT_FAILED_CHOLESKY \n - RET_INIT_FAILED_TQ \n - RET_INIT_FAILED_HOTSTART \n - RET_INIT_FAILED_INFEASIBILITY \n - RET_INIT_FAILED_UNBOUNDEDNESS \n - RET_MAX_NWSR_REACHED \n - RET_UNABLE_TO_READ_FILE */ -returnValue QProblem_initF( QProblem* _THIS, - const char* const H_file, /**< Name of file where Hessian matrix is stored. \n - If Hessian matrix is trivial, a NULL pointer can be passed. */ - const char* const g_file, /**< Name of file where gradient vector is stored. */ - const char* const A_file, /**< Name of file where constraint matrix is stored. */ - const char* const lb_file, /**< Name of file where lower bound vector. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const char* const ub_file, /**< Name of file where upper bound vector. \n - If no upper bounds exist, a NULL pointer can be passed. */ - const char* const lbA_file, /**< Name of file where lower constraints' bound vector. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const char* const ubA_file, /**< Name of file where upper constraints' bound vector. \n - If no upper constraints' bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations when using initial homotopy. - Output: Number of performed working set recalculations. */ - real_t* const cputime /**< Input: Maximum CPU time allowed for QP initialisation. \n - Output: CPU time spent for QP initialisation (if pointer passed). */ - ); - -/** Initialises a QP problem with given QP data and tries to solve it - * using at most nWSR iterations. Depending on the parameter constellation it: \n - * 1. 0, 0, 0 : starts with xOpt = 0, yOpt = 0 and gB/gC empty (or all implicit equality bounds), \n - * 2. xOpt, 0, 0 : starts with xOpt, yOpt = 0 and obtain gB/gC by "clipping", \n - * 3. 0, yOpt, 0 : starts with xOpt = 0, yOpt and obtain gB/gC from yOpt != 0, \n - * 4. 0, 0, gB/gC: starts with xOpt = 0, yOpt = 0 and gB/gC, \n - * 5. xOpt, yOpt, 0 : starts with xOpt, yOpt and obtain gB/gC from yOpt != 0, \n - * 6. xOpt, 0, gB/gC: starts with xOpt, yOpt = 0 and gB/gC, \n - * 7. xOpt, yOpt, gB/gC: starts with xOpt, yOpt and gB/gC (assume them to be consistent!) - * - * Note: This function internally calls solveInitialQP for initialisation! - * - * \return SUCCESSFUL_RETURN \n - RET_INIT_FAILED \n - RET_INIT_FAILED_CHOLESKY \n - RET_INIT_FAILED_TQ \n - RET_INIT_FAILED_HOTSTART \n - RET_INIT_FAILED_INFEASIBILITY \n - RET_INIT_FAILED_UNBOUNDEDNESS \n - RET_MAX_NWSR_REACHED \n - RET_INVALID_ARGUMENTS */ -returnValue QProblem_initMW( QProblem* _THIS, - DenseMatrix *_H, /**< Hessian matrix. \n - If Hessian matrix is trivial, a NULL pointer can be passed. */ - const real_t* const _g, /**< Gradient vector. */ - DenseMatrix *_A, /**< Constraint matrix. */ - const real_t* const _lb, /**< Lower bound vector (on variables). \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const _ub, /**< Upper bound vector (on variables). \n - If no upper bounds exist, a NULL pointer can be passed. */ - const real_t* const _lbA, /**< Lower constraints' bound vector. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const real_t* const _ubA, /**< Upper constraints' bound vector. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations when using initial homotopy. - * Output: Number of performed working set recalculations. */ - real_t* const cputime, /**< Input: Maximum CPU time allowed for QP initialisation. \n - Output: CPU time spent for QP initialisation. */ - const real_t* const xOpt, /**< Optimal primal solution vector. \n - (If a null pointer is passed, the old primal solution is kept!) */ - const real_t* const yOpt, /**< Optimal dual solution vector. \n - (If a null pointer is passed, the old dual solution is kept!) */ - Bounds* const guessedBounds, /**< Optimal working set of bounds for solution (xOpt,yOpt). */ - Constraints* const guessedConstraints, /**< Optimal working set of constraints for solution (xOpt,yOpt). */ - const real_t* const _R /**< Pre-computed (upper triangular) Cholesky factor of Hessian matrix. - The Cholesky factor must be stored in a real_t array of size nV*nV - in row-major format. Note: Only used if xOpt/yOpt and gB are NULL! \n - (If a null pointer is passed, Cholesky decomposition is computed internally!) */ - ); - -/** Initialises a QP problem with given QP data and tries to solve it - * using at most nWSR iterations. Depending on the parameter constellation it: \n - * 1. 0, 0, 0 : starts with xOpt = 0, yOpt = 0 and gB/gC empty (or all implicit equality bounds), \n - * 2. xOpt, 0, 0 : starts with xOpt, yOpt = 0 and obtain gB/gC by "clipping", \n - * 3. 0, yOpt, 0 : starts with xOpt = 0, yOpt and obtain gB/gC from yOpt != 0, \n - * 4. 0, 0, gB/gC: starts with xOpt = 0, yOpt = 0 and gB/gC, \n - * 5. xOpt, yOpt, 0 : starts with xOpt, yOpt and obtain gB/gC from yOpt != 0, \n - * 6. xOpt, 0, gB/gC: starts with xOpt, yOpt = 0 and gB/gC, \n - * 7. xOpt, yOpt, gB/gC: starts with xOpt, yOpt and gB/gC (assume them to be consistent!) - * - * Note: This function internally calls solveInitialQP for initialisation! - * - * \return SUCCESSFUL_RETURN \n - RET_INIT_FAILED \n - RET_INIT_FAILED_CHOLESKY \n - RET_INIT_FAILED_TQ \n - RET_INIT_FAILED_HOTSTART \n - RET_INIT_FAILED_INFEASIBILITY \n - RET_INIT_FAILED_UNBOUNDEDNESS \n - RET_MAX_NWSR_REACHED \n - RET_INVALID_ARGUMENTS */ -returnValue QProblem_initW( QProblem* _THIS, - real_t* const _H, /**< Hessian matrix. \n - If Hessian matrix is trivial, a NULL pointer can be passed. */ - const real_t* const _g, /**< Gradient vector. */ - real_t* const _A, /**< Constraint matrix. */ - const real_t* const _lb, /**< Lower bound vector (on variables). \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const _ub, /**< Upper bound vector (on variables). \n - If no upper bounds exist, a NULL pointer can be passed. */ - const real_t* const _lbA, /**< Lower constraints' bound vector. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const real_t* const _ubA, /**< Upper constraints' bound vector. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations when using initial homotopy. - * Output: Number of performed working set recalculations. */ - real_t* const cputime, /**< Input: Maximum CPU time allowed for QP initialisation. \n - Output: CPU time spent for QP initialisation. */ - const real_t* const xOpt, /**< Optimal primal solution vector. \n - (If a null pointer is passed, the old primal solution is kept!) */ - const real_t* const yOpt, /**< Optimal dual solution vector. \n - (If a null pointer is passed, the old dual solution is kept!) */ - Bounds* const guessedBounds, /**< Optimal working set of bounds for solution (xOpt,yOpt). */ - Constraints* const guessedConstraints, /**< Optimal working set of constraints for solution (xOpt,yOpt). */ - const real_t* const _R /**< Pre-computed (upper triangular) Cholesky factor of Hessian matrix. - The Cholesky factor must be stored in a real_t array of size nV*nV - in row-major format. Note: Only used if xOpt/yOpt and gB are NULL! \n - (If a null pointer is passed, Cholesky decomposition is computed internally!) */ - ); - -/** Initialises a QP problem with given QP data to be ream from files and tries to solve it - * using at most nWSR iterations. Depending on the parameter constellation it: \n - * 1. 0, 0, 0 : starts with xOpt = 0, yOpt = 0 and gB/gC empty (or all implicit equality bounds), \n - * 2. xOpt, 0, 0 : starts with xOpt, yOpt = 0 and obtain gB/gC by "clipping", \n - * 3. 0, yOpt, 0 : starts with xOpt = 0, yOpt and obtain gB/gC from yOpt != 0, \n - * 4. 0, 0, gB/gC: starts with xOpt = 0, yOpt = 0 and gB/gC, \n - * 5. xOpt, yOpt, 0 : starts with xOpt, yOpt and obtain gB/gC from yOpt != 0, \n - * 6. xOpt, 0, gB/gC: starts with xOpt, yOpt = 0 and gB/gC, \n - * 7. xOpt, yOpt, gB/gC: starts with xOpt, yOpt and gB/gC (assume them to be consistent!) - * - * Note: This function internally calls solveInitialQP for initialisation! - * - * \return SUCCESSFUL_RETURN \n - RET_INIT_FAILED \n - RET_INIT_FAILED_CHOLESKY \n - RET_INIT_FAILED_TQ \n - RET_INIT_FAILED_HOTSTART \n - RET_INIT_FAILED_INFEASIBILITY \n - RET_INIT_FAILED_UNBOUNDEDNESS \n - RET_MAX_NWSR_REACHED \n - RET_UNABLE_TO_READ_FILE */ -returnValue QProblem_initFW( QProblem* _THIS, - const char* const H_file, /**< Name of file where Hessian matrix is stored. \n - If Hessian matrix is trivial, a NULL pointer can be passed. */ - const char* const g_file, /**< Name of file where gradient vector is stored. */ - const char* const A_file, /**< Name of file where constraint matrix is stored. */ - const char* const lb_file, /**< Name of file where lower bound vector. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const char* const ub_file, /**< Name of file where upper bound vector. \n - If no upper bounds exist, a NULL pointer can be passed. */ - const char* const lbA_file, /**< Name of file where lower constraints' bound vector. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const char* const ubA_file, /**< Name of file where upper constraints' bound vector. \n - If no upper constraints' bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations when using initial homotopy. - Output: Number of performed working set recalculations. */ - real_t* const cputime, /**< Input: Maximum CPU time allowed for QP initialisation. \n - Output: CPU time spent for QP initialisation. */ - const real_t* const xOpt, /**< Optimal primal solution vector. \n - (If a null pointer is passed, the old primal solution is kept!) */ - const real_t* const yOpt, /**< Optimal dual solution vector. \n - (If a null pointer is passed, the old dual solution is kept!) */ - Bounds* const guessedBounds, /**< Optimal working set of bounds for solution (xOpt,yOpt). */ - Constraints* const guessedConstraints, /**< Optimal working set of constraints for solution (xOpt,yOpt). */ - const char* const R_file /**< Pre-computed (upper triangular) Cholesky factor of Hessian matrix. - The Cholesky factor must be stored in a real_t array of size nV*nV - in row-major format. Note: Only used if xOpt/yOpt and gB are NULL! \n - (If a null pointer is passed, Cholesky decomposition is computed internally!) */ - ); - -/** Solves an initialised QP sequence using the online active set strategy. - * QP solution is started from previous solution. - * - * Note: This function internally calls solveQP/solveRegularisedQP - * for solving an initialised QP! - * - * \return SUCCESSFUL_RETURN \n - RET_MAX_NWSR_REACHED \n - RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n - RET_HOTSTART_FAILED \n - RET_SHIFT_DETERMINATION_FAILED \n - RET_STEPDIRECTION_DETERMINATION_FAILED \n - RET_STEPLENGTH_DETERMINATION_FAILED \n - RET_HOMOTOPY_STEP_FAILED \n - RET_HOTSTART_STOPPED_INFEASIBILITY \n - RET_HOTSTART_STOPPED_UNBOUNDEDNESS */ -returnValue QProblem_hotstart( QProblem* _THIS, - const real_t* const g_new, /**< Gradient of neighbouring QP to be solved. */ - const real_t* const lb_new, /**< Lower bounds of neighbouring QP to be solved. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const ub_new, /**< Upper bounds of neighbouring QP to be solved. \n - If no upper bounds exist, a NULL pointer can be passed. */ - const real_t* const lbA_new, /**< Lower constraints' bounds of neighbouring QP to be solved. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const real_t* const ubA_new, /**< Upper constraints' bounds of neighbouring QP to be solved. \n - If no upper constraints' bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations; \n - Output: Number of performed working set recalculations. */ - real_t* const cputime /**< Input: Maximum CPU time allowed for QP solution. \n - Output: CPU time spent for QP solution (or to perform nWSR iterations). */ - ); - -/** Solves an initialised QP sequence using the online active set strategy, - * where QP data is read from files. QP solution is started from previous solution. - * - * Note: This function internally calls solveQP/solveRegularisedQP - * for solving an initialised QP! - * - * \return SUCCESSFUL_RETURN \n - RET_MAX_NWSR_REACHED \n - RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n - RET_HOTSTART_FAILED \n - RET_SHIFT_DETERMINATION_FAILED \n - RET_STEPDIRECTION_DETERMINATION_FAILED \n - RET_STEPLENGTH_DETERMINATION_FAILED \n - RET_HOMOTOPY_STEP_FAILED \n - RET_HOTSTART_STOPPED_INFEASIBILITY \n - RET_HOTSTART_STOPPED_UNBOUNDEDNESS \n - RET_UNABLE_TO_READ_FILE \n - RET_INVALID_ARGUMENTS */ -returnValue QProblem_hotstartF( QProblem* _THIS, - const char* const g_file, /**< Name of file where gradient, of neighbouring QP to be solved, is stored. */ - const char* const lb_file, /**< Name of file where lower bounds, of neighbouring QP to be solved, is stored. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const char* const ub_file, /**< Name of file where upper bounds, of neighbouring QP to be solved, is stored. \n - If no upper bounds exist, a NULL pointer can be passed. */ - const char* const lbA_file, /**< Name of file where lower constraints' bounds, of neighbouring QP to be solved, is stored. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const char* const ubA_file, /**< Name of file where upper constraints' bounds, of neighbouring QP to be solved, is stored. \n - If no upper constraints' bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations; \n - Output: Number of performed working set recalculations. */ - real_t* const cputime /**< Input: Maximum CPU time allowed for QP solution. \n - Output: CPU time spent for QP solution (or to perform nWSR iterations). */ - ); - -/** Solves an initialised QP sequence using the online active set strategy. - * By default, QP solution is started from previous solution. If a guess - * for the working set is provided, an initialised homotopy is performed. - * - * Note: This function internally calls solveQP/solveRegularisedQP - * for solving an initialised QP! - * - * \return SUCCESSFUL_RETURN \n - RET_MAX_NWSR_REACHED \n - RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n - RET_HOTSTART_FAILED \n - RET_SHIFT_DETERMINATION_FAILED \n - RET_STEPDIRECTION_DETERMINATION_FAILED \n - RET_STEPLENGTH_DETERMINATION_FAILED \n - RET_HOMOTOPY_STEP_FAILED \n - RET_HOTSTART_STOPPED_INFEASIBILITY \n - RET_HOTSTART_STOPPED_UNBOUNDEDNESS \n - RET_SETUP_AUXILIARYQP_FAILED */ -returnValue QProblem_hotstartW( QProblem* _THIS, - const real_t* const g_new, /**< Gradient of neighbouring QP to be solved. */ - const real_t* const lb_new, /**< Lower bounds of neighbouring QP to be solved. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const ub_new, /**< Upper bounds of neighbouring QP to be solved. \n - If no upper bounds exist, a NULL pointer can be passed. */ - const real_t* const lbA_new, /**< Lower constraints' bounds of neighbouring QP to be solved. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const real_t* const ubA_new, /**< Upper constraints' bounds of neighbouring QP to be solved. \n - If no upper constraints' bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations; \n - Output: Number of performed working set recalculations. */ - real_t* const cputime, /**< Input: Maximum CPU time allowed for QP solution. \n - Output: CPU time spent for QP solution (or to perform nWSR iterations). */ - Bounds* const guessedBounds, /**< Optimal working set of bounds for solution (xOpt,yOpt). \n - (If a null pointer is passed, the previous working set of bounds is kept!) */ - Constraints* const guessedConstraints /**< Optimal working set of constraints for solution (xOpt,yOpt). \n - (If a null pointer is passed, the previous working set of constraints is kept!) */ - ); - -/** Solves an initialised QP sequence using the online active set strategy, - * where QP data is read from files. - * By default, QP solution is started from previous solution. If a guess - * for the working set is provided, an initialised homotopy is performed. - * - * Note: This function internally calls solveQP/solveRegularisedQP - * for solving an initialised QP! - * - * \return SUCCESSFUL_RETURN \n - RET_MAX_NWSR_REACHED \n - RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n - RET_HOTSTART_FAILED \n - RET_SHIFT_DETERMINATION_FAILED \n - RET_STEPDIRECTION_DETERMINATION_FAILED \n - RET_STEPLENGTH_DETERMINATION_FAILED \n - RET_HOMOTOPY_STEP_FAILED \n - RET_HOTSTART_STOPPED_INFEASIBILITY \n - RET_HOTSTART_STOPPED_UNBOUNDEDNESS \n - RET_SETUP_AUXILIARYQP_FAILED \n - RET_UNABLE_TO_READ_FILE \n - RET_INVALID_ARGUMENTS */ -returnValue QProblem_hotstartFW( QProblem* _THIS, - const char* const g_file, /**< Name of file where gradient, of neighbouring QP to be solved, is stored. */ - const char* const lb_file, /**< Name of file where lower bounds, of neighbouring QP to be solved, is stored. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const char* const ub_file, /**< Name of file where upper bounds, of neighbouring QP to be solved, is stored. \n - If no upper bounds exist, a NULL pointer can be passed. */ - const char* const lbA_file, /**< Name of file where lower constraints' bounds, of neighbouring QP to be solved, is stored. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const char* const ubA_file, /**< Name of file where upper constraints' bounds, of neighbouring QP to be solved, is stored. \n - If no upper constraints' bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations; \n - Output: Number of performed working set recalculations. */ - real_t* const cputime, /**< Input: Maximum CPU time allowed for QP solution. \n - Output: CPU time spent for QP solution (or to perform nWSR iterations). */ - Bounds* const guessedBounds, /**< Optimal working set of bounds for solution (xOpt,yOpt). \n - (If a null pointer is passed, the previous working set of bounds is kept!) */ - Constraints* const guessedConstraints /**< Optimal working set of constraints for solution (xOpt,yOpt). \n - (If a null pointer is passed, the previous working set of constraints is kept!) */ - ); - - -/** Solves using the current working set - * \return SUCCESSFUL_RETURN \n - * RET_STEPDIRECTION_FAILED_TQ \n - * RET_STEPDIRECTION_FAILED_CHOLESKY \n - * RET_INVALID_ARGUMENTS */ -returnValue QProblem_solveCurrentEQP ( QProblem* _THIS, - const int n_rhs, /**< Number of consecutive right hand sides */ - const real_t* g_in, /**< Gradient of neighbouring QP to be solved. */ - const real_t* lb_in, /**< Lower bounds of neighbouring QP to be solved. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* ub_in, /**< Upper bounds of neighbouring QP to be solved. \n - If no upper bounds exist, a NULL pointer can be passed. */ - const real_t* lbA_in, /**< Lower constraints' bounds of neighbouring QP to be solved. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const real_t* ubA_in, /**< Upper constraints' bounds of neighbouring QP to be solved. \n */ - real_t* x_out, /**< Output: Primal solution */ - real_t* y_out /**< Output: Dual solution */ - ); - - - -/** Returns current constraints object of the QP (deep copy). - * \return SUCCESSFUL_RETURN \n - RET_QPOBJECT_NOT_SETUP */ -static inline returnValue QProblem_getConstraints( QProblem* _THIS, - Constraints* _constraints /** Output: Constraints object. */ - ); - - -/** Returns the number of constraints. - * \return Number of constraints. */ -static inline int QProblem_getNC( QProblem* _THIS ); - -/** Returns the number of (implicitly defined) equality constraints. - * \return Number of (implicitly defined) equality constraints. */ -static inline int QProblem_getNEC( QProblem* _THIS ); - -/** Returns the number of active constraints. - * \return Number of active constraints. */ -static inline int QProblem_getNAC( QProblem* _THIS ); - -/** Returns the number of inactive constraints. - * \return Number of inactive constraints. */ -static inline int QProblem_getNIAC( QProblem* _THIS ); - -/** Returns the dimension of null space. - * \return Dimension of null space. */ -int QProblem_getNZ( QProblem* _THIS ); - - -/** Returns the dual solution vector (deep copy). - * \return SUCCESSFUL_RETURN \n - RET_QP_NOT_SOLVED */ -returnValue QProblem_getDualSolution( QProblem* _THIS, - real_t* const yOpt /**< Output: Dual solution vector (if QP has been solved). */ - ); - - -/** Defines user-defined routine for calculating the constraint product A*x - * \return SUCCESSFUL_RETURN \n */ -returnValue QProblem_setConstraintProduct( QProblem* _THIS, - ConstraintProduct _constraintProduct - ); - - -/** Prints concise list of properties of the current QP. - * \return SUCCESSFUL_RETURN \n */ -returnValue QProblem_printProperties( QProblem* _THIS ); - - - -/** Writes a vector with the state of the working set -* \return SUCCESSFUL_RETURN */ -returnValue QProblem_getWorkingSet( QProblem* _THIS, - real_t* workingSet /** Output: array containing state of the working set. */ - ); - -/** Writes a vector with the state of the working set of bounds - * \return SUCCESSFUL_RETURN \n - * RET_INVALID_ARGUMENTS */ -returnValue QProblem_getWorkingSetBounds( QProblem* _THIS, - real_t* workingSetB /** Output: array containing state of the working set of bounds. */ - ); - -/** Writes a vector with the state of the working set of constraints - * \return SUCCESSFUL_RETURN \n - * RET_INVALID_ARGUMENTS */ -returnValue QProblem_getWorkingSetConstraints( QProblem* _THIS, - real_t* workingSetC /** Output: array containing state of the working set of constraints. */ - ); - - -/** Returns current bounds object of the QP (deep copy). - * \return SUCCESSFUL_RETURN \n - RET_QPOBJECT_NOT_SETUP */ -static inline returnValue QProblem_getBounds( QProblem* _THIS, - Bounds* _bounds /** Output: Bounds object. */ - ); - - -/** Returns the number of variables. - * \return Number of variables. */ -static inline int QProblem_getNV( QProblem* _THIS ); - -/** Returns the number of free variables. - * \return Number of free variables. */ -static inline int QProblem_getNFR( QProblem* _THIS ); - -/** Returns the number of fixed variables. - * \return Number of fixed variables. */ -static inline int QProblem_getNFX( QProblem* _THIS ); - -/** Returns the number of implicitly fixed variables. - * \return Number of implicitly fixed variables. */ -static inline int QProblem_getNFV( QProblem* _THIS ); - - -/** Returns the optimal objective function value. - * \return finite value: Optimal objective function value (QP was solved) \n - +infinity: QP was not yet solved */ -real_t QProblem_getObjVal( QProblem* _THIS ); - -/** Returns the objective function value at an arbitrary point x. - * \return Objective function value at point x */ -real_t QProblem_getObjValX( QProblem* _THIS, - const real_t* const _x /**< Point at which the objective function shall be evaluated. */ - ); - -/** Returns the primal solution vector. - * \return SUCCESSFUL_RETURN \n - RET_QP_NOT_SOLVED */ -returnValue QProblem_getPrimalSolution( QProblem* _THIS, - real_t* const xOpt /**< Output: Primal solution vector (if QP has been solved). */ - ); - - -/** Returns status of the solution process. - * \return Status of solution process. */ -static inline QProblemStatus QProblem_getStatus( QProblem* _THIS ); - - -/** Returns if the QProblem object is initialised. - * \return BT_TRUE: QProblem initialised \n - BT_FALSE: QProblem not initialised */ -static inline BooleanType QProblem_isInitialised( QProblem* _THIS ); - -/** Returns if the QP has been solved. - * \return BT_TRUE: QProblem solved \n - BT_FALSE: QProblem not solved */ -static inline BooleanType QProblem_isSolved( QProblem* _THIS ); - -/** Returns if the QP is infeasible. - * \return BT_TRUE: QP infeasible \n - BT_FALSE: QP feasible (or not known to be infeasible!) */ -static inline BooleanType QProblem_isInfeasible( QProblem* _THIS ); - -/** Returns if the QP is unbounded. - * \return BT_TRUE: QP unbounded \n - BT_FALSE: QP unbounded (or not known to be unbounded!) */ -static inline BooleanType QProblem_isUnbounded( QProblem* _THIS ); - - -/** Returns Hessian type flag (type is not determined due to _THIS call!). - * \return Hessian type. */ -static inline HessianType QProblem_getHessianType( QProblem* _THIS ); - -/** Changes the print level. - * \return SUCCESSFUL_RETURN */ -static inline returnValue QProblem_setHessianType( QProblem* _THIS, - HessianType _hessianType /**< New Hessian type. */ - ); - -/** Returns if the QP has been internally regularised. - * \return BT_TRUE: Hessian is internally regularised for QP solution \n - BT_FALSE: No internal Hessian regularisation is used for QP solution */ -static inline BooleanType QProblem_usingRegularisation( QProblem* _THIS ); - -/** Returns current options struct. - * \return Current options struct. */ -static inline Options QProblem_getOptions( QProblem* _THIS ); - -/** Overrides current options with given ones. - * \return SUCCESSFUL_RETURN */ -static inline returnValue QProblem_setOptions( QProblem* _THIS, - Options _options /**< New options. */ - ); - -/** Returns the print level. - * \return Print level. */ -static inline PrintLevel QProblem_getPrintLevel( QProblem* _THIS ); - -/** Changes the print level. - * \return SUCCESSFUL_RETURN */ -returnValue QProblem_setPrintLevel( QProblem* _THIS, - PrintLevel _printlevel /**< New print level. */ - ); - - -/** Returns the current number of QP problems solved. - * \return Number of QP problems solved. */ -static inline unsigned int QProblem_getCount( QProblem* _THIS ); - -/** Resets QP problem counter (to zero). - * \return SUCCESSFUL_RETURN. */ -static inline returnValue QProblem_resetCounter( QProblem* _THIS ); - - -/** Prints a list of all options and their current values. - * \return SUCCESSFUL_RETURN \n */ -returnValue QProblem_printOptions( QProblem* _THIS ); - - -/** Solves a QProblem whose QP data is assumed to be stored in the member variables. - * A guess for its primal/dual optimal solution vectors and the corresponding - * working sets of bounds and constraints can be provided. - * Note: This function is internally called by all init functions! - * \return SUCCESSFUL_RETURN \n - RET_INIT_FAILED \n - RET_INIT_FAILED_CHOLESKY \n - RET_INIT_FAILED_TQ \n - RET_INIT_FAILED_HOTSTART \n - RET_INIT_FAILED_INFEASIBILITY \n - RET_INIT_FAILED_UNBOUNDEDNESS \n - RET_MAX_NWSR_REACHED */ -returnValue QProblem_solveInitialQP( QProblem* _THIS, - const real_t* const xOpt, /**< Optimal primal solution vector.*/ - const real_t* const yOpt, /**< Optimal dual solution vector. */ - Bounds* const guessedBounds, /**< Optimal working set of bounds for solution (xOpt,yOpt). */ - Constraints* const guessedConstraints, /**< Optimal working set of constraints for solution (xOpt,yOpt). */ - const real_t* const _R, /**< Pre-computed (upper triangular) Cholesky factor of Hessian matrix. */ - int* nWSR, /**< Input: Maximum number of working set recalculations; \n - * Output: Number of performed working set recalculations. */ - real_t* const cputime /**< Input: Maximum CPU time allowed for QP solution. \n - * Output: CPU time spent for QP solution (or to perform nWSR iterations). */ - ); - -/** Solves QProblem using online active set strategy. - * Note: This function is internally called by all hotstart functions! - * \return SUCCESSFUL_RETURN \n - RET_MAX_NWSR_REACHED \n - RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n - RET_HOTSTART_FAILED \n - RET_SHIFT_DETERMINATION_FAILED \n - RET_STEPDIRECTION_DETERMINATION_FAILED \n - RET_STEPLENGTH_DETERMINATION_FAILED \n - RET_HOMOTOPY_STEP_FAILED \n - RET_HOTSTART_STOPPED_INFEASIBILITY \n - RET_HOTSTART_STOPPED_UNBOUNDEDNESS */ -returnValue QProblem_solveQP( QProblem* _THIS, - const real_t* const g_new, /**< Gradient of neighbouring QP to be solved. */ - const real_t* const lb_new, /**< Lower bounds of neighbouring QP to be solved. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const ub_new, /**< Upper bounds of neighbouring QP to be solved. \n - If no upper bounds exist, a NULL pointer can be passed. */ - const real_t* const lbA_new, /**< Lower constraints' bounds of neighbouring QP to be solved. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const real_t* const ubA_new, /**< Upper constraints' bounds of neighbouring QP to be solved. \n - If no upper constraints' bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations; \n - Output: Number of performed working set recalculations. */ - real_t* const cputime, /**< Input: Maximum CPU time allowed for QP solution. \n - Output: CPU time spent for QP solution (or to perform nWSR iterations). */ - int nWSRperformed, /**< Number of working set recalculations already performed to solve - this QP within previous solveQP() calls. This number is - always zero, except for successive calls from solveRegularisedQP() - or when using the far bound strategy. */ - BooleanType isFirstCall /**< Indicating whether this is the first call for current QP. */ - ); - - -/** Solves QProblem using online active set strategy. - * Note: This function is internally called by all hotstart functions! - * \return SUCCESSFUL_RETURN \n - RET_MAX_NWSR_REACHED \n - RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n - RET_HOTSTART_FAILED \n - RET_SHIFT_DETERMINATION_FAILED \n - RET_STEPDIRECTION_DETERMINATION_FAILED \n - RET_STEPLENGTH_DETERMINATION_FAILED \n - RET_HOMOTOPY_STEP_FAILED \n - RET_HOTSTART_STOPPED_INFEASIBILITY \n - RET_HOTSTART_STOPPED_UNBOUNDEDNESS */ -returnValue QProblem_solveRegularisedQP( QProblem* _THIS, - const real_t* const g_new, /**< Gradient of neighbouring QP to be solved. */ - const real_t* const lb_new, /**< Lower bounds of neighbouring QP to be solved. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const ub_new, /**< Upper bounds of neighbouring QP to be solved. \n - If no upper bounds exist, a NULL pointer can be passed. */ - const real_t* const lbA_new, /**< Lower constraints' bounds of neighbouring QP to be solved. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const real_t* const ubA_new, /**< Upper constraints' bounds of neighbouring QP to be solved. \n - If no upper constraints' bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations; \n - Output: Number of performed working set recalculations. */ - real_t* const cputime, /**< Input: Maximum CPU time allowed for QP solution. \n - Output: CPU time spent for QP solution (or to perform nWSR iterations). */ - int nWSRperformed, /**< Number of working set recalculations already performed to solve - this QP within previous solveRegularisedQP() calls. This number is - always zero, except for successive calls when using the far bound strategy. */ - BooleanType isFirstCall /**< Indicating whether this is the first call for current QP. */ - ); - - -/** Determines type of existing constraints and bounds (i.e. implicitly fixed, unbounded etc.). - * \return SUCCESSFUL_RETURN \n - RET_SETUPSUBJECTTOTYPE_FAILED */ -returnValue QProblem_setupSubjectToType( QProblem* _THIS ); - -/** Determines type of new constraints and bounds (i.e. implicitly fixed, unbounded etc.). - * \return SUCCESSFUL_RETURN \n - RET_SETUPSUBJECTTOTYPE_FAILED */ -returnValue QProblem_setupSubjectToTypeNew( QProblem* _THIS, - const real_t* const lb_new, /**< New lower bounds. */ - const real_t* const ub_new, /**< New upper bounds. */ - const real_t* const lbA_new, /**< New lower constraints' bounds. */ - const real_t* const ubA_new /**< New upper constraints' bounds. */ - ); - -/** Computes the Cholesky decomposition of the projected Hessian (i.e. R^T*R = Z^T*H*Z). - * Note: If Hessian turns out not to be positive definite, the Hessian type - * is set to HST_SEMIDEF accordingly. - * \return SUCCESSFUL_RETURN \n - * RET_HESSIAN_NOT_SPD \n - * RET_INDEXLIST_CORRUPTED */ -returnValue QProblem_computeProjectedCholesky( QProblem* _THIS ); - -/** Computes initial Cholesky decomposition of the projected Hessian making - * use of the function setupCholeskyDecomposition() or setupCholeskyDecompositionProjected(). - * \return SUCCESSFUL_RETURN \n - * RET_HESSIAN_NOT_SPD \n - * RET_INDEXLIST_CORRUPTED */ -returnValue QProblem_setupInitialCholesky( QProblem* _THIS ); - -/** Initialises TQ factorisation of A (i.e. A*Q = [0 T]) if NO constraint is active. - * \return SUCCESSFUL_RETURN \n - RET_INDEXLIST_CORRUPTED */ -returnValue QProblem_setupTQfactorisation( QProblem* _THIS ); - - -/** Obtains the desired working set for the auxiliary initial QP in - * accordance with the user specifications - * (assumes that member AX has already been initialised!) - * \return SUCCESSFUL_RETURN \n - RET_OBTAINING_WORKINGSET_FAILED \n - RET_INVALID_ARGUMENTS */ -returnValue QProblem_obtainAuxiliaryWorkingSet( QProblem* _THIS, - const real_t* const xOpt, /**< Optimal primal solution vector. - * If a NULL pointer is passed, all entries are assumed to be zero. */ - const real_t* const yOpt, /**< Optimal dual solution vector. - * If a NULL pointer is passed, all entries are assumed to be zero. */ - Bounds* const guessedBounds, /**< Guessed working set of bounds for solution (xOpt,yOpt). */ - Constraints* const guessedConstraints, /**< Guessed working set for solution (xOpt,yOpt). */ - Bounds* auxiliaryBounds, /**< Input: Allocated bound object. \n - * Ouput: Working set of constraints for auxiliary QP. */ - Constraints* auxiliaryConstraints /**< Input: Allocated bound object. \n - * Ouput: Working set for auxiliary QP. */ - ); - -/** Sets up bound and constraints data structures according to auxiliaryBounds/Constraints. - * (If the working set shall be setup afresh, make sure that - * bounds and constraints data structure have been resetted - * and the TQ factorisation has been initialised!) - * \return SUCCESSFUL_RETURN \n - RET_SETUP_WORKINGSET_FAILED \n - RET_INVALID_ARGUMENTS \n - RET_UNKNOWN_BUG */ -returnValue QProblem_setupAuxiliaryWorkingSet( QProblem* _THIS, - Bounds* const auxiliaryBounds, /**< Working set of bounds for auxiliary QP. */ - Constraints* const auxiliaryConstraints, /**< Working set of constraints for auxiliary QP. */ - BooleanType setupAfresh /**< Flag indicating if given working set shall be - * setup afresh or by updating the current one. */ - ); - -/** Sets up the optimal primal/dual solution of the auxiliary initial QP. - * \return SUCCESSFUL_RETURN */ -returnValue QProblem_setupAuxiliaryQPsolution( QProblem* _THIS, - const real_t* const xOpt, /**< Optimal primal solution vector. - * If a NULL pointer is passed, all entries are set to zero. */ - const real_t* const yOpt /**< Optimal dual solution vector. - * If a NULL pointer is passed, all entries are set to zero. */ - ); - -/** Sets up gradient of the auxiliary initial QP for given - * optimal primal/dual solution and given initial working set - * (assumes that members X, Y and BOUNDS, CONSTRAINTS have already been initialised!). - * \return SUCCESSFUL_RETURN */ -returnValue QProblem_setupAuxiliaryQPgradient( QProblem* _THIS ); - -/** Sets up (constraints') bounds of the auxiliary initial QP for given - * optimal primal/dual solution and given initial working set - * (assumes that members X, Y and BOUNDS, CONSTRAINTS have already been initialised!). - * \return SUCCESSFUL_RETURN \n - RET_UNKNOWN_BUG */ -returnValue QProblem_setupAuxiliaryQPbounds( QProblem* _THIS, - Bounds* const auxiliaryBounds, /**< Working set of bounds for auxiliary QP. */ - Constraints* const auxiliaryConstraints, /**< Working set of constraints for auxiliary QP. */ - BooleanType useRelaxation /**< Flag indicating if inactive (constraints') bounds shall be relaxed. */ - ); - - -/** Adds a constraint to active set. - * \return SUCCESSFUL_RETURN \n - RET_ADDCONSTRAINT_FAILED \n - RET_ADDCONSTRAINT_FAILED_INFEASIBILITY \n - RET_ENSURELI_FAILED */ -returnValue QProblem_addConstraint( QProblem* _THIS, - int number, /**< Number of constraint to be added to active set. */ - SubjectToStatus C_status, /**< Status of new active constraint. */ - BooleanType updateCholesky, /**< Flag indicating if Cholesky decomposition shall be updated. */ - BooleanType ensureLI /**< Ensure linear independence by exchange rules by default. */ - ); - -/** Checks if new active constraint to be added is linearly dependent from - * from row of the active constraints matrix. - * \return RET_LINEARLY_DEPENDENT \n - RET_LINEARLY_INDEPENDENT \n - RET_INDEXLIST_CORRUPTED */ -returnValue QProblem_addConstraint_checkLI( QProblem* _THIS, - int number /**< Number of constraint to be added to active set. */ - ); - -/** Ensures linear independence of constraint matrix when a new constraint is added. - * To _THIS end a bound or constraint is removed simultaneously if necessary. - * \return SUCCESSFUL_RETURN \n - RET_LI_RESOLVED \n - RET_ENSURELI_FAILED \n - RET_ENSURELI_FAILED_TQ \n - RET_ENSURELI_FAILED_NOINDEX \n - RET_REMOVE_FROM_ACTIVESET */ -returnValue QProblem_addConstraint_ensureLI( QProblem* _THIS, - int number, /**< Number of constraint to be added to active set. */ - SubjectToStatus C_status /**< Status of new active bound. */ - ); - -/** Adds a bound to active set. - * \return SUCCESSFUL_RETURN \n - RET_ADDBOUND_FAILED \n - RET_ADDBOUND_FAILED_INFEASIBILITY \n - RET_ENSURELI_FAILED */ -returnValue QProblem_addBound( QProblem* _THIS, - int number, /**< Number of bound to be added to active set. */ - SubjectToStatus B_status, /**< Status of new active bound. */ - BooleanType updateCholesky, /**< Flag indicating if Cholesky decomposition shall be updated. */ - BooleanType ensureLI /**< Ensure linear independence by exchange rules by default. */ - ); - -/** Checks if new active bound to be added is linearly dependent from - * from row of the active constraints matrix. - * \return RET_LINEARLY_DEPENDENT \n - RET_LINEARLY_INDEPENDENT */ -returnValue QProblem_addBound_checkLI( QProblem* _THIS, - int number /**< Number of bound to be added to active set. */ - ); - -/** Ensures linear independence of constraint matrix when a new bound is added. - * To _THIS end a bound or constraint is removed simultaneously if necessary. - * \return SUCCESSFUL_RETURN \n - RET_LI_RESOLVED \n - RET_ENSURELI_FAILED \n - RET_ENSURELI_FAILED_TQ \n - RET_ENSURELI_FAILED_NOINDEX \n - RET_REMOVE_FROM_ACTIVESET */ -returnValue QProblem_addBound_ensureLI( QProblem* _THIS, - int number, /**< Number of bound to be added to active set. */ - SubjectToStatus B_status /**< Status of new active bound. */ - ); - -/** Removes a constraint from active set. - * \return SUCCESSFUL_RETURN \n - RET_CONSTRAINT_NOT_ACTIVE \n - RET_REMOVECONSTRAINT_FAILED \n - RET_HESSIAN_NOT_SPD */ -returnValue QProblem_removeConstraint( QProblem* _THIS, - int number, /**< Number of constraint to be removed from active set. */ - BooleanType updateCholesky, /**< Flag indicating if Cholesky decomposition shall be updated. */ - BooleanType allowFlipping, /**< Flag indicating if flipping bounds are allowed. */ - BooleanType ensureNZC /**< Flag indicating if non-zero curvature is ensured by exchange rules. */ - ); - -/** Removes a bounds from active set. - * \return SUCCESSFUL_RETURN \n - RET_BOUND_NOT_ACTIVE \n - RET_HESSIAN_NOT_SPD \n - RET_REMOVEBOUND_FAILED */ -returnValue QProblem_removeBound( QProblem* _THIS, - int number, /**< Number of bound to be removed from active set. */ - BooleanType updateCholesky, /**< Flag indicating if Cholesky decomposition shall be updated. */ - BooleanType allowFlipping, /**< Flag indicating if flipping bounds are allowed. */ - BooleanType ensureNZC /**< Flag indicating if non-zero curvature is ensured by exchange rules. */ - ); - - -/** Performs robustified ratio test yield the maximum possible step length - * along the homotopy path. - * \return SUCCESSFUL_RETURN */ -returnValue QProblem_performPlainRatioTest( QProblem* _THIS, - int nIdx, /**< Number of ratios to be checked. */ - const int* const idxList, /**< Array containing the indices of all ratios to be checked. */ - const real_t* const num, /**< Array containing all numerators for performing the ratio test. */ - const real_t* const den, /**< Array containing all denominators for performing the ratio test. */ - real_t epsNum, /**< Numerator tolerance. */ - real_t epsDen, /**< Denominator tolerance. */ - real_t* t, /**< Output: Maximum possible step length along the homotopy path. */ - int* BC_idx /**< Output: Index of blocking constraint. */ - ); - - -/** Ensure non-zero curvature by primal jump. - * \return SUCCESSFUL_RETURN \n - * RET_HOTSTART_STOPPED_UNBOUNDEDNESS */ -returnValue QProblem_ensureNonzeroCurvature( QProblem* _THIS, - BooleanType removeBoundNotConstraint, /**< SubjectTo to be removed is a bound. */ - int remIdx, /**< Index of bound/constraint to be removed. */ - BooleanType* exchangeHappened, /**< Output: Exchange was necessary to ensure. */ - BooleanType* addBoundNotConstraint, /**< SubjectTo to be added is a bound. */ - int* addIdx, /**< Index of bound/constraint to be added. */ - SubjectToStatus* addStatus /**< Status of bound/constraint to be added. */ - ); - - -/** Solves the system Ta = b or T^Ta = b where T is a reverse upper triangular matrix. - * \return SUCCESSFUL_RETURN \n - RET_DIV_BY_ZERO */ -returnValue QProblem_backsolveT( QProblem* _THIS, - const real_t* const b, /**< Right hand side vector. */ - BooleanType transposed, /**< Indicates if the transposed system shall be solved. */ - real_t* const a /**< Output: Solution vector */ - ); - - -/** Determines step direction of the shift of the QP data. - * \return SUCCESSFUL_RETURN */ -returnValue QProblem_determineDataShift( QProblem* _THIS, - const real_t* const g_new, /**< New gradient vector. */ - const real_t* const lbA_new, /**< New lower constraints' bounds. */ - const real_t* const ubA_new, /**< New upper constraints' bounds. */ - const real_t* const lb_new, /**< New lower bounds. */ - const real_t* const ub_new, /**< New upper bounds. */ - real_t* const delta_g, /**< Output: Step direction of gradient vector. */ - real_t* const delta_lbA, /**< Output: Step direction of lower constraints' bounds. */ - real_t* const delta_ubA, /**< Output: Step direction of upper constraints' bounds. */ - real_t* const delta_lb, /**< Output: Step direction of lower bounds. */ - real_t* const delta_ub, /**< Output: Step direction of upper bounds. */ - BooleanType* Delta_bC_isZero, /**< Output: Indicates if active constraints' bounds are to be shifted. */ - BooleanType* Delta_bB_isZero /**< Output: Indicates if active bounds are to be shifted. */ - ); - -/** Determines step direction of the homotopy path. - * \return SUCCESSFUL_RETURN \n - RET_STEPDIRECTION_FAILED_TQ \n - RET_STEPDIRECTION_FAILED_CHOLESKY */ -returnValue QProblem_determineStepDirection( QProblem* _THIS, - const real_t* const delta_g, /**< Step direction of gradient vector. */ - const real_t* const delta_lbA, /**< Step direction of lower constraints' bounds. */ - const real_t* const delta_ubA, /**< Step direction of upper constraints' bounds. */ - const real_t* const delta_lb, /**< Step direction of lower bounds. */ - const real_t* const delta_ub, /**< Step direction of upper bounds. */ - BooleanType Delta_bC_isZero, /**< Indicates if active constraints' bounds are to be shifted. */ - BooleanType Delta_bB_isZero, /**< Indicates if active bounds are to be shifted. */ - real_t* const delta_xFX, /**< Output: Primal homotopy step direction of fixed variables. */ - real_t* const delta_xFR, /**< Output: Primal homotopy step direction of free variables. */ - real_t* const delta_yAC, /**< Output: Dual homotopy step direction of active constraints' multiplier. */ - real_t* const delta_yFX /**< Output: Dual homotopy step direction of fixed variables' multiplier. */ - ); - -/** Determines the maximum possible step length along the homotopy path - * and performs _THIS step (without changing working set). - * \return SUCCESSFUL_RETURN \n - * RET_ERROR_IN_CONSTRAINTPRODUCT \n - * RET_QP_INFEASIBLE */ -returnValue QProblem_performStep( QProblem* _THIS, - const real_t* const delta_g, /**< Step direction of gradient. */ - const real_t* const delta_lbA, /**< Step direction of lower constraints' bounds. */ - const real_t* const delta_ubA, /**< Step direction of upper constraints' bounds. */ - const real_t* const delta_lb, /**< Step direction of lower bounds. */ - const real_t* const delta_ub, /**< Step direction of upper bounds. */ - const real_t* const delta_xFX, /**< Primal homotopy step direction of fixed variables. */ - const real_t* const delta_xFR, /**< Primal homotopy step direction of free variables. */ - const real_t* const delta_yAC, /**< Dual homotopy step direction of active constraints' multiplier. */ - const real_t* const delta_yFX, /**< Dual homotopy step direction of fixed variables' multiplier. */ - int* BC_idx, /**< Output: Index of blocking constraint. */ - SubjectToStatus* BC_status, /**< Output: Status of blocking constraint. */ - BooleanType* BC_isBound /**< Output: Indicates if blocking constraint is a bound. */ - ); - -/** Updates the active set. - * \return SUCCESSFUL_RETURN \n - RET_REMOVE_FROM_ACTIVESET_FAILED \n - RET_ADD_TO_ACTIVESET_FAILED */ -returnValue QProblem_changeActiveSet( QProblem* _THIS, - int BC_idx, /**< Index of blocking constraint. */ - SubjectToStatus BC_status, /**< Status of blocking constraint. */ - BooleanType BC_isBound /**< Indicates if blocking constraint is a bound. */ - ); - - -/** Compute relative length of homotopy in data space for termination - * criterion. - * \return Relative length in data space. */ -real_t QProblem_getRelativeHomotopyLength( QProblem* _THIS, - const real_t* const g_new, /**< Final gradient. */ - const real_t* const lb_new, /**< Final lower variable bounds. */ - const real_t* const ub_new, /**< Final upper variable bounds. */ - const real_t* const lbA_new, /**< Final lower constraint bounds. */ - const real_t* const ubA_new /**< Final upper constraint bounds. */ - ); - - -/** Ramping Strategy to avoid ties. Modifies homotopy start without - * changing current active set. - * \return SUCCESSFUL_RETURN */ -returnValue QProblem_performRamping( QProblem* _THIS ); - - -/** ... */ -returnValue QProblem_updateFarBounds( QProblem* _THIS, - real_t curFarBound, /**< ... */ - int nRamp, /**< ... */ - const real_t* const lb_new, /**< ... */ - real_t* const lb_new_far, /**< ... */ - const real_t* const ub_new, /**< ... */ - real_t* const ub_new_far, /**< ... */ - const real_t* const lbA_new, /**< ... */ - real_t* const lbA_new_far, /**< ... */ - const real_t* const ubA_new, /**< ... */ - real_t* const ubA_new_far /**< ... */ - ); - -/** ... */ -returnValue QProblemBCPY_updateFarBounds( QProblem* _THIS, - real_t curFarBound, /**< ... */ - int nRamp, /**< ... */ - const real_t* const lb_new, /**< ... */ - real_t* const lb_new_far, /**< ... */ - const real_t* const ub_new, /**< ... */ - real_t* const ub_new_far /**< ... */ - ); - - - -/** Performs robustified ratio test yield the maximum possible step length - * along the homotopy path. - * \return SUCCESSFUL_RETURN */ -returnValue QProblem_performRatioTestC( QProblem* _THIS, - int nIdx, /**< Number of ratios to be checked. */ - const int* const idxList, /**< Array containing the indices of all ratios to be checked. */ - Constraints* const subjectTo, /**< Constraint object corresponding to ratios to be checked. */ - const real_t* const num, /**< Array containing all numerators for performing the ratio test. */ - const real_t* const den, /**< Array containing all denominators for performing the ratio test. */ - real_t epsNum, /**< Numerator tolerance. */ - real_t epsDen, /**< Denominator tolerance. */ - real_t* t, /**< Output: Maximum possible step length along the homotopy path. */ - int* BC_idx /**< Output: Index of blocking constraint. */ - ); - - -/** Drift correction at end of each active set iteration - * \return SUCCESSFUL_RETURN */ -returnValue QProblem_performDriftCorrection( QProblem* _THIS ); - - -/** Updates QP vectors, working sets and internal data structures in order to - start from an optimal solution corresponding to initial guesses of the working - set for bounds and constraints. - * \return SUCCESSFUL_RETURN \n - * RET_SETUP_AUXILIARYQP_FAILED \n - RET_INVALID_ARGUMENTS */ -returnValue QProblem_setupAuxiliaryQP( QProblem* _THIS, - Bounds* const guessedBounds, /**< Initial guess for working set of bounds. */ - Constraints* const guessedConstraints /**< Initial guess for working set of constraints. */ - ); - -/** Determines if it is more efficient to refactorise the matrices when - * hotstarting or not (i.e. better to update the existing factorisations). - * \return BT_TRUE iff matrices shall be refactorised afresh - */ -BooleanType QProblem_shallRefactorise( QProblem* _THIS, - Bounds* const guessedBounds, /**< Guessed new working set of bounds. */ - Constraints* const guessedConstraints /**< Guessed new working set of constraints. */ - ); - -/** Setups internal QP data. - * \return SUCCESSFUL_RETURN \n - RET_INVALID_ARGUMENTS \n - RET_UNKNONW_BUG */ -returnValue QProblem_setupQPdataM( QProblem* _THIS, - DenseMatrix *_H, /**< Hessian matrix. \n - If Hessian matrix is trivial,a NULL pointer can be passed. */ - const real_t* const _g, /**< Gradient vector. */ - DenseMatrix *_A, /**< Constraint matrix. */ - const real_t* const _lb, /**< Lower bound vector (on variables). \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const _ub, /**< Upper bound vector (on variables). \n - If no upper bounds exist, a NULL pointer can be passed. */ - const real_t* const _lbA, /**< Lower constraints' bound vector. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const real_t* const _ubA /**< Upper constraints' bound vector. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - ); - - -/** Sets up dense internal QP data. If the current Hessian is trivial - * (i.e. HST_ZERO or HST_IDENTITY) but a non-trivial one is given, - * memory for Hessian is allocated and it is set to the given one. - * \return SUCCESSFUL_RETURN \n - RET_INVALID_ARGUMENTS \n - RET_UNKNONW_BUG */ -returnValue QProblem_setupQPdata( QProblem* _THIS, - real_t* const _H, /**< Hessian matrix. \n - If Hessian matrix is trivial,a NULL pointer can be passed. */ - const real_t* const _g, /**< Gradient vector. */ - real_t* const _A, /**< Constraint matrix. */ - const real_t* const _lb, /**< Lower bound vector (on variables). \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const _ub, /**< Upper bound vector (on variables). \n - If no upper bounds exist, a NULL pointer can be passed. */ - const real_t* const _lbA, /**< Lower constraints' bound vector. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const real_t* const _ubA /**< Upper constraints' bound vector. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - ); - -/** Sets up internal QP data by loading it from files. If the current Hessian - * is trivial (i.e. HST_ZERO or HST_IDENTITY) but a non-trivial one is given, - * memory for Hessian is allocated and it is set to the given one. - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_OPEN_FILE \n - RET_UNABLE_TO_READ_FILE \n - RET_INVALID_ARGUMENTS \n - RET_UNKNONW_BUG */ -returnValue QProblem_setupQPdataFromFile( QProblem* _THIS, - const char* const H_file, /**< Name of file where Hessian matrix, of neighbouring QP to be solved, is stored. \n - If Hessian matrix is trivial,a NULL pointer can be passed. */ - const char* const g_file, /**< Name of file where gradient, of neighbouring QP to be solved, is stored. */ - const char* const A_file, /**< Name of file where constraint matrix, of neighbouring QP to be solved, is stored. */ - const char* const lb_file, /**< Name of file where lower bounds, of neighbouring QP to be solved, is stored. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const char* const ub_file, /**< Name of file where upper bounds, of neighbouring QP to be solved, is stored. \n - If no upper bounds exist, a NULL pointer can be passed. */ - const char* const lbA_file, /**< Name of file where lower constraints' bounds, of neighbouring QP to be solved, is stored. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const char* const ubA_file /**< Name of file where upper constraints' bounds, of neighbouring QP to be solved, is stored. \n - If no upper constraints' bounds exist, a NULL pointer can be passed. */ - ); - -/** Loads new QP vectors from files (internal members are not affected!). - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_OPEN_FILE \n - RET_UNABLE_TO_READ_FILE \n - RET_INVALID_ARGUMENTS */ -returnValue QProblem_loadQPvectorsFromFile( QProblem* _THIS, - const char* const g_file, /**< Name of file where gradient, of neighbouring QP to be solved, is stored. */ - const char* const lb_file, /**< Name of file where lower bounds, of neighbouring QP to be solved, is stored. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const char* const ub_file, /**< Name of file where upper bounds, of neighbouring QP to be solved, is stored. \n - If no upper bounds exist, a NULL pointer can be passed. */ - const char* const lbA_file, /**< Name of file where lower constraints' bounds, of neighbouring QP to be solved, is stored. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const char* const ubA_file, /**< Name of file where upper constraints' bounds, of neighbouring QP to be solved, is stored. \n - If no upper constraints' bounds exist, a NULL pointer can be passed. */ - real_t* const g_new, /**< Output: Gradient of neighbouring QP to be solved. */ - real_t* const lb_new, /**< Output: Lower bounds of neighbouring QP to be solved */ - real_t* const ub_new, /**< Output: Upper bounds of neighbouring QP to be solved */ - real_t* const lbA_new, /**< Output: Lower constraints' bounds of neighbouring QP to be solved */ - real_t* const ubA_new /**< Output: Upper constraints' bounds of neighbouring QP to be solved */ - ); - - -/** Prints concise information on the current iteration. - * \return SUCCESSFUL_RETURN \n */ -returnValue QProblem_printIteration( QProblem* _THIS, - int iter, /**< Number of current iteration. */ - int BC_idx, /**< Index of blocking constraint. */ - SubjectToStatus BC_status, /**< Status of blocking constraint. */ - BooleanType BC_isBound, /**< Indicates if blocking constraint is a bound. */ - real_t homotopyLength, /**< Current homotopy distance. */ - BooleanType isFirstCall /**< Indicating whether this is the first call for current QP. */ - ); - - -/** Sets constraint matrix of the QP. \n - Note: Also internal vector Ax is recomputed! - * \return SUCCESSFUL_RETURN \n - * RET_INVALID_ARGUMENTS */ -static inline returnValue QProblem_setAM( QProblem* _THIS, - DenseMatrix *A_new /**< New constraint matrix. */ - ); - -/** Sets dense constraint matrix of the QP. \n - Note: Also internal vector Ax is recomputed! - * \return SUCCESSFUL_RETURN \n - * RET_INVALID_ARGUMENTS */ -static inline returnValue QProblem_setA( QProblem* _THIS, - real_t* const A_new /**< New dense constraint matrix (with correct dimension!). */ - ); - - -/** Sets constraints' lower bound vector of the QP. - * \return SUCCESSFUL_RETURN \n - * RET_QPOBJECT_NOT_SETUP */ -static inline returnValue QProblem_setLBA( QProblem* _THIS, - const real_t* const lbA_new /**< New constraints' lower bound vector (with correct dimension!). */ - ); - -/** Changes single entry of lower constraints' bound vector of the QP. - * \return SUCCESSFUL_RETURN \n - * RET_QPOBJECT_NOT_SETUP \n - * RET_INDEX_OUT_OF_BOUNDS */ -static inline returnValue QProblem_setLBAn( QProblem* _THIS, - int number, /**< Number of entry to be changed. */ - real_t value /**< New value for entry of lower constraints' bound vector (with correct dimension!). */ - ); - -/** Sets constraints' upper bound vector of the QP. - * \return SUCCESSFUL_RETURN \n - * RET_QPOBJECT_NOT_SETUP */ -static inline returnValue QProblem_setUBA( QProblem* _THIS, - const real_t* const ubA_new /**< New constraints' upper bound vector (with correct dimension!). */ - ); - -/** Changes single entry of upper constraints' bound vector of the QP. - * \return SUCCESSFUL_RETURN \n - * RET_QPOBJECT_NOT_SETUP \n - * RET_INDEX_OUT_OF_BOUNDS */ -static inline returnValue QProblem_setUBAn( QProblem* _THIS, - int number, /**< Number of entry to be changed. */ - real_t value /**< New value for entry of upper constraints' bound vector (with correct dimension!). */ - ); - - -/** Decides if lower bounds are smaller than upper bounds - * - * \return SUCCESSFUL_RETURN \n - * RET_QP_INFEASIBLE */ -returnValue QProblem_areBoundsConsistent( QProblem* _THIS, - const real_t* const lb, /**< Vector of lower bounds*/ - const real_t* const ub, /**< Vector of upper bounds*/ - const real_t* const lbA, /**< Vector of lower constraints*/ - const real_t* const ubA /**< Vector of upper constraints*/ - ); - - -/** Drops the blocking bound/constraint that led to infeasibility, or finds another - * bound/constraint to drop according to drop priorities. - * \return SUCCESSFUL_RETURN \n - */ -returnValue QProblem_dropInfeasibles ( QProblem* _THIS, - int BC_number, /**< Number of the bound or constraint to be added */ - SubjectToStatus BC_status, /**< New status of the bound or constraint to be added */ - BooleanType BC_isBound, /**< Whether a bound or a constraint is to be added */ - real_t *xiB, - real_t *xiC - ); - - -/** If Hessian type has been set by the user, nothing is done. - * Otherwise the Hessian type is set to HST_IDENTITY, HST_ZERO, or - * HST_POSDEF (default), respectively. - * \return SUCCESSFUL_RETURN \n - RET_HESSIAN_INDEFINITE */ -returnValue QProblem_determineHessianType( QProblem* _THIS ); - -/** Computes the Cholesky decomposition of the (simply projected) Hessian - * (i.e. R^T*R = Z^T*H*Z). It only works in the case where Z is a simple - * projection matrix! - * Note: If Hessian turns out not to be positive definite, the Hessian type - * is set to HST_SEMIDEF accordingly. - * \return SUCCESSFUL_RETURN \n - * RET_HESSIAN_NOT_SPD \n - * RET_INDEXLIST_CORRUPTED */ -returnValue QProblemBCPY_computeCholesky( QProblem* _THIS ); - -/** Obtains the desired working set for the auxiliary initial QP in - * accordance with the user specifications - * \return SUCCESSFUL_RETURN \n - RET_OBTAINING_WORKINGSET_FAILED \n - RET_INVALID_ARGUMENTS */ -returnValue QProblemBCPY_obtainAuxiliaryWorkingSet( QProblem* _THIS, - const real_t* const xOpt, /**< Optimal primal solution vector. - * If a NULL pointer is passed, all entries are assumed to be zero. */ - const real_t* const yOpt, /**< Optimal dual solution vector. - * If a NULL pointer is passed, all entries are assumed to be zero. */ - Bounds* const guessedBounds, /**< Guessed working set for solution (xOpt,yOpt). */ - Bounds* auxiliaryBounds /**< Input: Allocated bound object. \n - * Output: Working set for auxiliary QP. */ - ); - - -/** Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix. - * \return SUCCESSFUL_RETURN \n - RET_DIV_BY_ZERO */ -returnValue QProblem_backsolveR( QProblem* _THIS, - const real_t* const b, /**< Right hand side vector. */ - BooleanType transposed, /**< Indicates if the transposed system shall be solved. */ - real_t* const a /**< Output: Solution vector */ - ); - -/** Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix. \n - * Special variant for the case that _THIS function is called from within "removeBound()". - * \return SUCCESSFUL_RETURN \n - RET_DIV_BY_ZERO */ -returnValue QProblem_backsolveRrem( QProblem* _THIS, - const real_t* const b, /**< Right hand side vector. */ - BooleanType transposed, /**< Indicates if the transposed system shall be solved. */ - BooleanType removingBound, /**< Indicates if function is called from "removeBound()". */ - real_t* const a /**< Output: Solution vector */ - ); - - -/** Determines step direction of the shift of the QP data. - * \return SUCCESSFUL_RETURN */ -returnValue QProblemBCPY_determineDataShift( QProblem* _THIS, - const real_t* const g_new, /**< New gradient vector. */ - const real_t* const lb_new, /**< New lower bounds. */ - const real_t* const ub_new, /**< New upper bounds. */ - real_t* const delta_g, /**< Output: Step direction of gradient vector. */ - real_t* const delta_lb, /**< Output: Step direction of lower bounds. */ - real_t* const delta_ub, /**< Output: Step direction of upper bounds. */ - BooleanType* Delta_bB_isZero /**< Output: Indicates if active bounds are to be shifted. */ - ); - - -/** Sets up internal QP data. - * \return SUCCESSFUL_RETURN \n - RET_INVALID_ARGUMENTS */ -returnValue QProblemBCPY_setupQPdataM( QProblem* _THIS, - DenseMatrix *_H, /**< Hessian matrix.*/ - const real_t* const _g, /**< Gradient vector. */ - const real_t* const _lb, /**< Lower bounds (on variables). \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const _ub /**< Upper bounds (on variables). \n - If no upper bounds exist, a NULL pointer can be passed. */ - ); - -/** Sets up internal QP data. If the current Hessian is trivial - * (i.e. HST_ZERO or HST_IDENTITY) but a non-trivial one is given, - * memory for Hessian is allocated and it is set to the given one. - * \return SUCCESSFUL_RETURN \n - RET_INVALID_ARGUMENTS \n - RET_NO_HESSIAN_SPECIFIED */ -returnValue QProblemBCPY_setupQPdata( QProblem* _THIS, - real_t* const _H, /**< Hessian matrix. \n - If Hessian matrix is trivial,a NULL pointer can be passed. */ - const real_t* const _g, /**< Gradient vector. */ - const real_t* const _lb, /**< Lower bounds (on variables). \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const _ub /**< Upper bounds (on variables). \n - If no upper bounds exist, a NULL pointer can be passed. */ - ); - -/** Sets up internal QP data by loading it from files. If the current Hessian - * is trivial (i.e. HST_ZERO or HST_IDENTITY) but a non-trivial one is given, - * memory for Hessian is allocated and it is set to the given one. - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_OPEN_FILE \n - RET_UNABLE_TO_READ_FILE \n - RET_INVALID_ARGUMENTS \n - RET_NO_HESSIAN_SPECIFIED */ -returnValue QProblemBCPY_setupQPdataFromFile( QProblem* _THIS, - const char* const H_file, /**< Name of file where Hessian matrix, of neighbouring QP to be solved, is stored. \n - If Hessian matrix is trivial,a NULL pointer can be passed. */ - const char* const g_file, /**< Name of file where gradient, of neighbouring QP to be solved, is stored. */ - const char* const lb_file, /**< Name of file where lower bounds, of neighbouring QP to be solved, is stored. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const char* const ub_file /**< Name of file where upper bounds, of neighbouring QP to be solved, is stored. \n - If no upper bounds exist, a NULL pointer can be passed. */ - ); - -/** Loads new QP vectors from files (internal members are not affected!). - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_OPEN_FILE \n - RET_UNABLE_TO_READ_FILE \n - RET_INVALID_ARGUMENTS */ -returnValue QProblemBCPY_loadQPvectorsFromFile( QProblem* _THIS, - const char* const g_file, /**< Name of file where gradient, of neighbouring QP to be solved, is stored. */ - const char* const lb_file, /**< Name of file where lower bounds, of neighbouring QP to be solved, is stored. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const char* const ub_file, /**< Name of file where upper bounds, of neighbouring QP to be solved, is stored. \n - If no upper bounds exist, a NULL pointer can be passed. */ - real_t* const g_new, /**< Output: Gradient of neighbouring QP to be solved. */ - real_t* const lb_new, /**< Output: Lower bounds of neighbouring QP to be solved */ - real_t* const ub_new /**< Output: Upper bounds of neighbouring QP to be solved */ - ); - - -/** Sets internal infeasibility flag and throws given error in case the far bound - * strategy is not enabled (as QP might actually not be infeasible in _THIS case). - * \return RET_HOTSTART_STOPPED_INFEASIBILITY \n - RET_ENSURELI_FAILED_CYCLING \n - RET_ENSURELI_FAILED_NOINDEX */ -returnValue QProblem_setInfeasibilityFlag( QProblem* _THIS, - returnValue returnvalue, /**< Returnvalue to be tunneled. */ - BooleanType doThrowError /**< Flag forcing to throw an error. */ - ); - - -/** Determines if next QP iteration can be performed within given CPU time limit. - * \return BT_TRUE: CPU time limit is exceeded, stop QP solution. \n - BT_FALSE: Sufficient CPU time for next QP iteration. */ -BooleanType QProblem_isCPUtimeLimitExceeded( QProblem* _THIS, - const real_t* const cputime, /**< Maximum CPU time allowed for QP solution. */ - real_t starttime, /**< Start time of current QP solution. */ - int nWSR /**< Number of working set recalculations performed so far. */ - ); - - -/** Regularise Hessian matrix by adding a scaled identity matrix to it. - * \return SUCCESSFUL_RETURN \n - RET_HESSIAN_ALREADY_REGULARISED */ -returnValue QProblem_regulariseHessian( QProblem* _THIS ); - - -/** Sets Hessian matrix of the QP. - * \return SUCCESSFUL_RETURN */ -static inline returnValue QProblem_setHM( QProblem* _THIS, - DenseMatrix* H_new /**< New Hessian matrix. */ - ); - -/** Sets dense Hessian matrix of the QP. - * If a null pointer is passed and - * a) hessianType is HST_IDENTITY, nothing is done, - * b) hessianType is not HST_IDENTITY, Hessian matrix is set to zero. - * \return SUCCESSFUL_RETURN */ -static inline returnValue QProblem_setH( QProblem* _THIS, - real_t* const H_new /**< New dense Hessian matrix (with correct dimension!). */ - ); - -/** Changes gradient vector of the QP. - * \return SUCCESSFUL_RETURN \n - * RET_INVALID_ARGUMENTS */ -static inline returnValue QProblem_setG( QProblem* _THIS, - const real_t* const g_new /**< New gradient vector (with correct dimension!). */ - ); - -/** Changes lower bound vector of the QP. - * \return SUCCESSFUL_RETURN \n - * RET_INVALID_ARGUMENTS */ -static inline returnValue QProblem_setLB( QProblem* _THIS, - const real_t* const lb_new /**< New lower bound vector (with correct dimension!). */ - ); - -/** Changes single entry of lower bound vector of the QP. - * \return SUCCESSFUL_RETURN \n - RET_INDEX_OUT_OF_BOUNDS */ -static inline returnValue QProblem_setLBn( QProblem* _THIS, - int number, /**< Number of entry to be changed. */ - real_t value /**< New value for entry of lower bound vector. */ - ); - -/** Changes upper bound vector of the QP. - * \return SUCCESSFUL_RETURN \n - * RET_INVALID_ARGUMENTS */ -static inline returnValue QProblem_setUB( QProblem* _THIS, - const real_t* const ub_new /**< New upper bound vector (with correct dimension!). */ - ); - -/** Changes single entry of upper bound vector of the QP. - * \return SUCCESSFUL_RETURN \n - RET_INDEX_OUT_OF_BOUNDS */ -static inline returnValue QProblem_setUBn( QProblem* _THIS, - int number, /**< Number of entry to be changed. */ - real_t value /**< New value for entry of upper bound vector. */ - ); - - - -/** Compute relative length of homotopy in data space for termination - * criterion. - * \return Relative length in data space. */ -real_t QProblemBCPY_getRelativeHomotopyLength( QProblem* _THIS, - const real_t* const g_new, /**< Final gradient. */ - const real_t* const lb_new, /**< Final lower variable bounds. */ - const real_t* const ub_new /**< Final upper variable bounds. */ - ); - - - -/** Performs robustified ratio test yield the maximum possible step length - * along the homotopy path. - * \return SUCCESSFUL_RETURN */ -returnValue QProblem_performRatioTestB( QProblem* _THIS, - int nIdx, /**< Number of ratios to be checked. */ - const int* const idxList, /**< Array containing the indices of all ratios to be checked. */ - Bounds* const subjectTo, /**< Bound object corresponding to ratios to be checked. */ - const real_t* const num, /**< Array containing all numerators for performing the ratio test. */ - const real_t* const den, /**< Array containing all denominators for performing the ratio test. */ - real_t epsNum, /**< Numerator tolerance. */ - real_t epsDen, /**< Denominator tolerance. */ - real_t* t, /**< Output: Maximum possible step length along the homotopy path. */ - int* BC_idx /**< Output: Index of blocking constraint. */ - ); - -/** Checks whether given ratio is blocking, i.e. limits the maximum step length - * along the homotopy path to a value lower than given one. - * \return SUCCESSFUL_RETURN */ -static inline BooleanType QProblem_isBlocking( QProblem* _THIS, - real_t num, /**< Numerator for performing the ratio test. */ - real_t den, /**< Denominator for performing the ratio test. */ - real_t epsNum, /**< Numerator tolerance. */ - real_t epsDen, /**< Denominator tolerance. */ - real_t* t /**< Input: Current maximum step length along the homotopy path, - * Output: Updated maximum possible step length along the homotopy path. */ - ); - - -/** ... - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_OPEN_FILE */ -returnValue QProblem_writeQpDataIntoMatFile( QProblem* _THIS, - const char* const filename /**< Mat file name. */ - ); - -/** ... -* \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_OPEN_FILE */ -returnValue QProblem_writeQpWorkspaceIntoMatFile( QProblem* _THIS, - const char* const filename /**< Mat file name. */ - ); - - -/* - * g e t B o u n d s - */ -static inline returnValue QProblem_getBounds( QProblem* _THIS, Bounds* _bounds ) -{ - int nV = QProblem_getNV( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - _bounds = _THIS->bounds; - - return SUCCESSFUL_RETURN; -} - - -/* - * g e t N V - */ -static inline int QProblem_getNV( QProblem* _THIS ) -{ - return Bounds_getNV( _THIS->bounds ); -} - - -/* - * g e t N F R - */ -static inline int QProblem_getNFR( QProblem* _THIS ) -{ - return Bounds_getNFR( _THIS->bounds ); -} - - -/* - * g e t N F X - */ -static inline int QProblem_getNFX( QProblem* _THIS ) -{ - return Bounds_getNFX( _THIS->bounds ); -} - - -/* - * g e t N F V - */ -static inline int QProblem_getNFV( QProblem* _THIS ) -{ - return Bounds_getNFV( _THIS->bounds ); -} - - -/* - * g e t S t a t u s - */ -static inline QProblemStatus QProblem_getStatus( QProblem* _THIS ) -{ - return _THIS->status; -} - - -/* - * i s I n i t i a l i s e d - */ -static inline BooleanType QProblem_isInitialised( QProblem* _THIS ) -{ - if ( _THIS->status == QPS_NOTINITIALISED ) - return BT_FALSE; - else - return BT_TRUE; -} - - -/* - * i s S o l v e d - */ -static inline BooleanType QProblem_isSolved( QProblem* _THIS ) -{ - if ( _THIS->status == QPS_SOLVED ) - return BT_TRUE; - else - return BT_FALSE; -} - - -/* - * i s I n f e a s i b l e - */ -static inline BooleanType QProblem_isInfeasible( QProblem* _THIS ) -{ - return _THIS->infeasible; -} - - -/* - * i s U n b o u n d e d - */ -static inline BooleanType QProblem_isUnbounded( QProblem* _THIS ) -{ - return _THIS->unbounded; -} - - -/* - * g e t H e s s i a n T y p e - */ -static inline HessianType QProblem_getHessianType( QProblem* _THIS ) -{ - return _THIS->hessianType; -} - - -/* - * s e t H e s s i a n T y p e - */ -static inline returnValue QProblem_setHessianType( QProblem* _THIS, HessianType _hessianType ) -{ - _THIS->hessianType = _hessianType; - return SUCCESSFUL_RETURN; -} - - -/* - * u s i n g R e g u l a r i s a t i o n - */ -static inline BooleanType QProblem_usingRegularisation( QProblem* _THIS ) -{ - if ( _THIS->regVal > QPOASES_ZERO ) - return BT_TRUE; - else - return BT_FALSE; -} - - -/* - * g e t O p t i o n s - */ -static inline Options QProblem_getOptions( QProblem* _THIS ) -{ - return _THIS->options; -} - - -/* - * s e t O p t i o n s - */ -static inline returnValue QProblem_setOptions( QProblem* _THIS, - Options _options - ) -{ - OptionsCPY( &_options,&(_THIS->options) ); - Options_ensureConsistency( &(_THIS->options) ); - - QProblem_setPrintLevel( _THIS,_THIS->options.printLevel ); - - return SUCCESSFUL_RETURN; -} - - -/* - * g e t P r i n t L e v e l - */ -static inline PrintLevel QProblem_getPrintLevel( QProblem* _THIS ) -{ - return _THIS->options.printLevel; -} - - -/* - * g e t C o u n t - */ -static inline unsigned int QProblem_getCount( QProblem* _THIS ) -{ - return _THIS->count; -} - - -/* - * r e s e t C o u n t e r - */ -static inline returnValue QProblem_resetCounter( QProblem* _THIS ) -{ - _THIS->count = 0; - return SUCCESSFUL_RETURN; -} - - - -/***************************************************************************** - * P R O T E C T E D * - *****************************************************************************/ - - -/* - * s e t H - */ -static inline returnValue QProblem_setHM( QProblem* _THIS, DenseMatrix* H_new ) -{ - if ( H_new == 0 ) - return QProblem_setH( _THIS,(real_t*)0 ); - else - return QProblem_setH( _THIS,DenseMatrix_getVal(H_new) ); -} - - -/* - * s e t H - */ -static inline returnValue QProblem_setH( QProblem* _THIS, real_t* const H_new ) -{ - /* if null pointer is passed, Hessian is set to zero matrix - * (or stays identity matrix) */ - if ( H_new == 0 ) - { - if ( _THIS->hessianType == HST_IDENTITY ) - return SUCCESSFUL_RETURN; - - _THIS->hessianType = HST_ZERO; - - _THIS->H = 0; - } - else - { - DenseMatrixCON( _THIS->H,QProblem_getNV( _THIS ),QProblem_getNV( _THIS ),QProblem_getNV( _THIS ),H_new ); - } - - return SUCCESSFUL_RETURN; -} - - -/* - * s e t G - */ -static inline returnValue QProblem_setG( QProblem* _THIS, const real_t* const g_new ) -{ - unsigned int nV = (unsigned int)QProblem_getNV( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( g_new == 0 ) - return THROWERROR( RET_INVALID_ARGUMENTS ); - - memcpy( _THIS->g,g_new,nV*sizeof(real_t) ); - - return SUCCESSFUL_RETURN; -} - - -/* - * s e t L B - */ -static inline returnValue QProblem_setLB( QProblem* _THIS, const real_t* const lb_new ) -{ - unsigned int i; - unsigned int nV = (unsigned int)QProblem_getNV( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( lb_new != 0 ) - { - memcpy( _THIS->lb,lb_new,nV*sizeof(real_t) ); - } - else - { - /* if no lower bounds are specified, set them to -infinity */ - for( i=0; ilb[i] = -QPOASES_INFTY; - } - - return SUCCESSFUL_RETURN; -} - - -/* - * s e t L B - */ -static inline returnValue QProblem_setLBn( QProblem* _THIS, int number, real_t value ) -{ - int nV = QProblem_getNV( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( ( number >= 0 ) && ( number < nV ) ) - { - _THIS->lb[number] = value; - return SUCCESSFUL_RETURN; - } - else - { - return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); - } -} - - -/* - * s e t U B - */ -static inline returnValue QProblem_setUB( QProblem* _THIS, const real_t* const ub_new ) -{ - unsigned int i; - unsigned int nV = (unsigned int)QProblem_getNV( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( ub_new != 0 ) - { - memcpy( _THIS->ub,ub_new,nV*sizeof(real_t) ); - } - else - { - /* if no upper bounds are specified, set them to infinity */ - for( i=0; iub[i] = QPOASES_INFTY; - } - - return SUCCESSFUL_RETURN; -} - - -/* - * s e t U B - */ -static inline returnValue QProblem_setUBn( QProblem* _THIS, int number, real_t value ) -{ - int nV = QProblem_getNV( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( ( number >= 0 ) && ( number < nV ) ) - { - _THIS->ub[number] = value; - - return SUCCESSFUL_RETURN; - } - else - { - return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); - } -} - - - -/* - * i s B l o c k i n g - */ -static inline BooleanType QProblem_isBlocking( QProblem* _THIS, - real_t num, - real_t den, - real_t epsNum, - real_t epsDen, - real_t* t - ) -{ - if ( ( den >= epsDen ) && ( num >= epsNum ) ) - { - if ( num < (*t)*den ) - return BT_TRUE; - } - - return BT_FALSE; -} - - - -/* - * g e t C o n s t r a i n t s - */ -static inline returnValue QProblem_getConstraints( QProblem* _THIS, Constraints* _constraints ) -{ - int nV = QProblem_getNV( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - ConstraintsCPY( _THIS->constraints,_constraints ); - - return SUCCESSFUL_RETURN; -} - - - -/* - * g e t N C - */ -static inline int QProblem_getNC( QProblem* _THIS ) -{ - return Constraints_getNC( _THIS->constraints ); -} - - -/* - * g e t N E C - */ -static inline int QProblem_getNEC( QProblem* _THIS ) -{ - return Constraints_getNEC( _THIS->constraints ); -} - - -/* - * g e t N A C - */ -static inline int QProblem_getNAC( QProblem* _THIS ) -{ - return Constraints_getNAC( _THIS->constraints ); -} - - -/* - * g e t N I A C - */ -static inline int QProblem_getNIAC( QProblem* _THIS ) -{ - return Constraints_getNIAC( _THIS->constraints ); -} - - - -/***************************************************************************** - * P R O T E C T E D * - *****************************************************************************/ - - -/* - * s e t A - */ -static inline returnValue QProblem_setAM( QProblem* _THIS, DenseMatrix *A_new ) -{ - if ( A_new == 0 ) - return QProblem_setA( _THIS,(real_t*)0 ); - else - return QProblem_setA( _THIS,DenseMatrix_getVal(A_new) ); -} - - -/* - * s e t A - */ -static inline returnValue QProblem_setA( QProblem* _THIS, real_t* const A_new ) -{ - int j; - int nV = QProblem_getNV( _THIS ); - int nC = QProblem_getNC( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( A_new == 0 ) - return THROWERROR( RET_INVALID_ARGUMENTS ); - - DenseMatrixCON( _THIS->A,QProblem_getNC( _THIS ),QProblem_getNV( _THIS ),QProblem_getNV( _THIS ),A_new ); - - DenseMatrix_times( _THIS->A,1, 1.0, _THIS->x, nV, 0.0, _THIS->Ax, nC); - - for( j=0; jAx_u[j] = _THIS->ubA[j] - _THIS->Ax[j]; - _THIS->Ax_l[j] = _THIS->Ax[j] - _THIS->lbA[j]; - - /* (ckirches) disable constraints with empty rows */ - if ( qpOASES_isZero( DenseMatrix_getRowNorm( _THIS->A,j,2 ),QPOASES_ZERO ) == BT_TRUE ) - Constraints_setType( _THIS->constraints,j,ST_DISABLED ); - } - - return SUCCESSFUL_RETURN; -} - - -/* - * s e t L B A - */ -static inline returnValue QProblem_setLBA( QProblem* _THIS, const real_t* const lbA_new ) -{ - unsigned int i; - unsigned int nV = (unsigned int)QProblem_getNV( _THIS ); - unsigned int nC = (unsigned int)QProblem_getNC( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( lbA_new != 0 ) - { - memcpy( _THIS->lbA,lbA_new,nC*sizeof(real_t) ); - } - else - { - /* if no lower constraints' bounds are specified, set them to -infinity */ - for( i=0; ilbA[i] = -QPOASES_INFTY; - } - - return SUCCESSFUL_RETURN; -} - - -/* - * s e t L B A - */ -static inline returnValue QProblem_setLBAn( QProblem* _THIS, int number, real_t value ) -{ - int nV = QProblem_getNV( _THIS ); - int nC = QProblem_getNC( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( ( number >= 0 ) && ( number < nC ) ) - { - _THIS->lbA[number] = value; - return SUCCESSFUL_RETURN; - } - else - return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); -} - - -/* - * s e t U B A - */ -static inline returnValue QProblem_setUBA( QProblem* _THIS, const real_t* const ubA_new ) -{ - unsigned int i; - unsigned int nV = (unsigned int)QProblem_getNV( _THIS ); - unsigned int nC = (unsigned int)QProblem_getNC( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( ubA_new != 0 ) - { - memcpy( _THIS->ubA,ubA_new,nC*sizeof(real_t) ); - } - else - { - /* if no upper constraints' bounds are specified, set them to infinity */ - for( i=0; iubA[i] = QPOASES_INFTY; - } - - return SUCCESSFUL_RETURN; -} - - -/* - * s e t U B A - */ -static inline returnValue QProblem_setUBAn( QProblem* _THIS, int number, real_t value ) -{ - int nV = QProblem_getNV( _THIS ); - int nC = QProblem_getNC( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( ( number >= 0 ) && ( number < nC ) ) - { - _THIS->ubA[number] = value; - return SUCCESSFUL_RETURN; - } - else - return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); -} - - -END_NAMESPACE_QPOASES - - -#endif /* QPOASES_QPROBLEM_H */ - - -/* - * end of file - */ diff --git a/third_party/acados/include/qpOASES_e/QProblemB.h b/third_party/acados/include/qpOASES_e/QProblemB.h deleted file mode 100644 index ee5157dda7..0000000000 --- a/third_party/acados/include/qpOASES_e/QProblemB.h +++ /dev/null @@ -1,1641 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/QProblemB.h - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - * - * Declaration of the QProblemB class which is able to use the newly - * developed online active set strategy for parametric quadratic programming - * for problems with (simple) bounds only. - */ - - - -#ifndef QPOASES_QPROBLEMB_H -#define QPOASES_QPROBLEMB_H - - -#include -#include -#include -#include - - -BEGIN_NAMESPACE_QPOASES - -typedef struct { - Bounds *emptyBounds; - Bounds *auxiliaryBounds; - - real_t *ub_new_far; - real_t *lb_new_far; - - real_t *g_new; - real_t *lb_new; - real_t *ub_new; - - real_t *g_new2; - real_t *lb_new2; - real_t *ub_new2; - - real_t *Hx; - - real_t *_H; - - real_t *g_original; - real_t *lb_original; - real_t *ub_original; - - real_t *delta_xFR; - real_t *delta_xFX; - real_t *delta_yFX; - real_t *delta_g; - real_t *delta_lb; - real_t *delta_ub; - - real_t *gMod; - - real_t *num; - real_t *den; - - real_t *rhs; - real_t *r; -} QProblemB_ws; - -int QProblemB_ws_calculateMemorySize( unsigned int nV ); - -char *QProblemB_ws_assignMemory( unsigned int nV, QProblemB_ws **mem, void *raw_memory ); - -QProblemB_ws *QProblemB_ws_createMemory( unsigned int nV ); - - -/** - * \brief Implements the online active set strategy for box-constrained QPs. - * - * Class for setting up and solving quadratic programs with bounds (= box constraints) only. - * The main feature is the possibility to use the newly developed online active set strategy - * for parametric quadratic programming. - * - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - */ -typedef struct -{ - QProblemB_ws *ws; - Bounds *bounds; /**< Data structure for problem's bounds. */ - Flipper *flipper; /**< Struct for making a temporary copy of the matrix factorisations. */ - - DenseMatrix* H; /**< Hessian matrix pointer. */ - - Options options; /**< Struct containing all user-defined options for solving QPs. */ - TabularOutput tabularOutput; /**< Struct storing information for tabular output (printLevel == PL_TABULAR). */ - - real_t *g; /**< Gradient. */ - real_t *lb; /**< Lower bound vector (on variables). */ - real_t *ub; /**< Upper bound vector (on variables). */ - - real_t *R; /**< Cholesky factor of H (i.e. H = R^T*R). */ - - real_t *x; /**< Primal solution vector. */ - real_t *y; /**< Dual solution vector. */ - - real_t *delta_xFR_TMP; /**< Temporary for determineStepDirection */ - - real_t tau; /**< Last homotopy step length. */ - real_t regVal; /**< Holds the offset used to regularise Hessian matrix (zero by default). */ - - real_t ramp0; /**< Start value for Ramping Strategy. */ - real_t ramp1; /**< Final value for Ramping Strategy. */ - - QProblemStatus status; /**< Current status of the solution process. */ - HessianType hessianType; /**< Type of Hessian matrix. */ - - BooleanType haveCholesky; /**< Flag indicating whether Cholesky decomposition has already been setup. */ - BooleanType infeasible; /**< QP infeasible? */ - BooleanType unbounded; /**< QP unbounded? */ - - int rampOffset; /**< Offset index for Ramping. */ - unsigned int count; /**< Counts the number of hotstart function calls (internal usage only!). */ -} QProblemB; - -int QProblemB_calculateMemorySize( unsigned int nV ); - -char *QProblemB_assignMemory( unsigned int nV, QProblemB **mem, void *raw_memory ); - -QProblemB *QProblemB_createMemory( unsigned int nV ); - - -/** Constructor which takes the QP dimension and Hessian type - * information. If the Hessian is the zero (i.e. HST_ZERO) or the - * identity matrix (i.e. HST_IDENTITY), respectively, no memory - * is allocated for it and a NULL pointer can be passed for it - * to the init() functions. */ -void QProblemBCON( QProblemB* _THIS, - int _nV, /**< Number of variables. */ - HessianType _hessianType /**< Type of Hessian matrix. */ - ); - -void QProblemBCPY( QProblemB* FROM, - QProblemB* TO - ); - - -/** Clears all data structures of QProblemB except for QP data. - * \return SUCCESSFUL_RETURN \n - RET_RESET_FAILED */ -returnValue QProblemB_reset( QProblemB* _THIS ); - - -/** Initialises a simply bounded QP problem with given QP data and tries to solve it - * using at most nWSR iterations. - * - * Note: This function internally calls solveInitialQP for initialisation! - * - * \return SUCCESSFUL_RETURN \n - RET_INIT_FAILED \n - RET_INIT_FAILED_CHOLESKY \n - RET_INIT_FAILED_HOTSTART \n - RET_INIT_FAILED_INFEASIBILITY \n - RET_INIT_FAILED_UNBOUNDEDNESS \n - RET_MAX_NWSR_REACHED \n - RET_INVALID_ARGUMENTS */ -returnValue QProblemB_initM( QProblemB* _THIS, - DenseMatrix *_H, /**< Hessian matrix. */ - const real_t* const _g, /**< Gradient vector. */ - const real_t* const _lb, /**< Lower bounds (on variables). \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const _ub, /**< Upper bounds (on variables). \n - If no upper bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations when using initial homotopy. \n - Output: Number of performed working set recalculations. */ - real_t* const cputime /**< Input: Maximum CPU time allowed for QP initialisation. \n - Output: CPU time spent for QP initialisation (if pointer passed). */ - ); - -/** Initialises a simply bounded QP problem with given QP data and tries to solve it - * using at most nWSR iterations. - * - * Note: This function internally calls solveInitialQP for initialisation! - * - * \return SUCCESSFUL_RETURN \n - RET_INIT_FAILED \n - RET_INIT_FAILED_CHOLESKY \n - RET_INIT_FAILED_HOTSTART \n - RET_INIT_FAILED_INFEASIBILITY \n - RET_INIT_FAILED_UNBOUNDEDNESS \n - RET_MAX_NWSR_REACHED \n - RET_INVALID_ARGUMENTS */ -returnValue QProblemB_init( QProblemB* _THIS, - real_t* const _H, /**< Hessian matrix. \n - If Hessian matrix is trivial, a NULL pointer can be passed. */ - const real_t* const _g, /**< Gradient vector. */ - const real_t* const _lb, /**< Lower bounds (on variables). \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const _ub, /**< Upper bounds (on variables). \n - If no upper bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations when using initial homotopy. \n - Output: Number of performed working set recalculations. */ - real_t* const cputime /**< Input: Maximum CPU time allowed for QP initialisation. \n - Output: CPU time spent for QP initialisation (if pointer passed). */ - ); - -/** Initialises a simply bounded QP problem with given QP data to be read from files and solves it - * using at most nWSR iterations. - * - * Note: This function internally calls solveInitialQP for initialisation! - * - * \return SUCCESSFUL_RETURN \n - RET_INIT_FAILED \n - RET_INIT_FAILED_CHOLESKY \n - RET_INIT_FAILED_HOTSTART \n - RET_INIT_FAILED_INFEASIBILITY \n - RET_INIT_FAILED_UNBOUNDEDNESS \n - RET_MAX_NWSR_REACHED \n - RET_UNABLE_TO_READ_FILE */ -returnValue QProblemB_initF( QProblemB* _THIS, - const char* const H_file, /**< Name of file where Hessian matrix is stored. \n - If Hessian matrix is trivial, a NULL pointer can be passed. */ - const char* const g_file, /**< Name of file where gradient vector is stored. */ - const char* const lb_file, /**< Name of file where lower bound vector. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const char* const ub_file, /**< Name of file where upper bound vector. \n - If no upper bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations when using initial homotopy. \n - Output: Number of performed working set recalculations. */ - real_t* const cputime /**< Input: Maximum CPU time allowed for QP initialisation. \n - Output: CPU time spent for QP initialisation (if pointer passed). */ - ); - -/** Initialises a simply bounded QP problem with given QP data and tries to solve it - * using at most nWSR iterations. Depending on the parameter constellation it: \n - * 1. 0, 0, 0 : starts with xOpt = 0, yOpt = 0 and gB empty (or all implicit equality bounds), \n - * 2. xOpt, 0, 0 : starts with xOpt, yOpt = 0 and obtain gB by "clipping", \n - * 3. 0, yOpt, 0 : starts with xOpt = 0, yOpt and obtain gB from yOpt != 0, \n - * 4. 0, 0, gB: starts with xOpt = 0, yOpt = 0 and gB, \n - * 5. xOpt, yOpt, 0 : starts with xOpt, yOpt and obtain gB from yOpt != 0, \n - * 6. xOpt, 0, gB: starts with xOpt, yOpt = 0 and gB, \n - * 7. xOpt, yOpt, gB: starts with xOpt, yOpt and gB (assume them to be consistent!) - * - * Note: This function internally calls solveInitialQP for initialisation! - * - * \return SUCCESSFUL_RETURN \n - RET_INIT_FAILED \n - RET_INIT_FAILED_CHOLESKY \n - RET_INIT_FAILED_HOTSTART \n - RET_INIT_FAILED_INFEASIBILITY \n - RET_INIT_FAILED_UNBOUNDEDNESS \n - RET_MAX_NWSR_REACHED \n - RET_INVALID_ARGUMENTS */ -returnValue QProblemB_initMW( QProblemB* _THIS, - DenseMatrix *_H, /**< Hessian matrix. */ - const real_t* const _g, /**< Gradient vector. */ - const real_t* const _lb, /**< Lower bounds (on variables). \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const _ub, /**< Upper bounds (on variables). \n - If no upper bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations when using initial homotopy. \n - Output: Number of performed working set recalculations. */ - real_t* const cputime, /**< Input: Maximum CPU time allowed for QP initialisation. \n - Output: CPU time spent for QP initialisation. */ - const real_t* const xOpt, /**< Optimal primal solution vector. A NULL pointer can be passed. \n - (If a null pointer is passed, the old primal solution is kept!) */ - const real_t* const yOpt, /**< Optimal dual solution vector. A NULL pointer can be passed. \n - (If a null pointer is passed, the old dual solution is kept!) */ - Bounds* const guessedBounds, /**< Optimal working set of bounds for solution (xOpt,yOpt). \n - (If a null pointer is passed, all bounds are assumed inactive!) */ - const real_t* const _R /**< Pre-computed (upper triangular) Cholesky factor of Hessian matrix. - The Cholesky factor must be stored in a real_t array of size nV*nV - in row-major format. Note: Only used if xOpt/yOpt and gB are NULL! \n - (If a null pointer is passed, Cholesky decomposition is computed internally!) */ - ); - -/** Initialises a simply bounded QP problem with given QP data and tries to solve it - * using at most nWSR iterations. Depending on the parameter constellation it: \n - * 1. 0, 0, 0 : starts with xOpt = 0, yOpt = 0 and gB empty (or all implicit equality bounds), \n - * 2. xOpt, 0, 0 : starts with xOpt, yOpt = 0 and obtain gB by "clipping", \n - * 3. 0, yOpt, 0 : starts with xOpt = 0, yOpt and obtain gB from yOpt != 0, \n - * 4. 0, 0, gB: starts with xOpt = 0, yOpt = 0 and gB, \n - * 5. xOpt, yOpt, 0 : starts with xOpt, yOpt and obtain gB from yOpt != 0, \n - * 6. xOpt, 0, gB: starts with xOpt, yOpt = 0 and gB, \n - * 7. xOpt, yOpt, gB: starts with xOpt, yOpt and gB (assume them to be consistent!) - * - * Note: This function internally calls solveInitialQP for initialisation! - * - * \return SUCCESSFUL_RETURN \n - RET_INIT_FAILED \n - RET_INIT_FAILED_CHOLESKY \n - RET_INIT_FAILED_HOTSTART \n - RET_INIT_FAILED_INFEASIBILITY \n - RET_INIT_FAILED_UNBOUNDEDNESS \n - RET_MAX_NWSR_REACHED \n - RET_INVALID_ARGUMENTS */ -returnValue QProblemB_initW( QProblemB* _THIS, - real_t* const _H, /**< Hessian matrix. \n - If Hessian matrix is trivial, a NULL pointer can be passed. */ - const real_t* const _g, /**< Gradient vector. */ - const real_t* const _lb, /**< Lower bounds (on variables). \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const _ub, /**< Upper bounds (on variables). \n - If no upper bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations when using initial homotopy. \n - Output: Number of performed working set recalculations. */ - real_t* const cputime, /**< Input: Maximum CPU time allowed for QP initialisation. \n - Output: CPU time spent for QP initialisation. */ - const real_t* const xOpt, /**< Optimal primal solution vector. A NULL pointer can be passed. \n - (If a null pointer is passed, the old primal solution is kept!) */ - const real_t* const yOpt, /**< Optimal dual solution vector. A NULL pointer can be passed. \n - (If a null pointer is passed, the old dual solution is kept!) */ - Bounds* const guessedBounds, /**< Optimal working set of bounds for solution (xOpt,yOpt). \n - (If a null pointer is passed, all bounds are assumed inactive!) */ - const real_t* const _R /**< Pre-computed (upper triangular) Cholesky factor of Hessian matrix. - The Cholesky factor must be stored in a real_t array of size nV*nV - in row-major format. Note: Only used if xOpt/yOpt and gB are NULL! \n - (If a null pointer is passed, Cholesky decomposition is computed internally!) */ - ); - -/** Initialises a simply bounded QP problem with given QP data to be read from files and solves it - * using at most nWSR iterations. Depending on the parameter constellation it: \n - * 1. 0, 0, 0 : starts with xOpt = 0, yOpt = 0 and gB empty (or all implicit equality bounds), \n - * 2. xOpt, 0, 0 : starts with xOpt, yOpt = 0 and obtain gB by "clipping", \n - * 3. 0, yOpt, 0 : starts with xOpt = 0, yOpt and obtain gB from yOpt != 0, \n - * 4. 0, 0, gB: starts with xOpt = 0, yOpt = 0 and gB, \n - * 5. xOpt, yOpt, 0 : starts with xOpt, yOpt and obtain gB from yOpt != 0, \n - * 6. xOpt, 0, gB: starts with xOpt, yOpt = 0 and gB, \n - * 7. xOpt, yOpt, gB: starts with xOpt, yOpt and gB (assume them to be consistent!) - * - * Note: This function internally calls solveInitialQP for initialisation! - * - * \return SUCCESSFUL_RETURN \n - RET_INIT_FAILED \n - RET_INIT_FAILED_CHOLESKY \n - RET_INIT_FAILED_HOTSTART \n - RET_INIT_FAILED_INFEASIBILITY \n - RET_INIT_FAILED_UNBOUNDEDNESS \n - RET_MAX_NWSR_REACHED \n - RET_UNABLE_TO_READ_FILE */ -returnValue QProblemB_initFW( QProblemB* _THIS, - const char* const H_file, /**< Name of file where Hessian matrix is stored. \n - If Hessian matrix is trivial, a NULL pointer can be passed. */ - const char* const g_file, /**< Name of file where gradient vector is stored. */ - const char* const lb_file, /**< Name of file where lower bound vector. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const char* const ub_file, /**< Name of file where upper bound vector. \n - If no upper bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations when using initial homotopy. \n - Output: Number of performed working set recalculations. */ - real_t* const cputime, /**< Input: Maximum CPU time allowed for QP initialisation. \n - Output: CPU time spent for QP initialisation. */ - const real_t* const xOpt, /**< Optimal primal solution vector. A NULL pointer can be passed. \n - (If a null pointer is passed, the old primal solution is kept!) */ - const real_t* const yOpt, /**< Optimal dual solution vector. A NULL pointer can be passed. \n - (If a null pointer is passed, the old dual solution is kept!) */ - Bounds* const guessedBounds, /**< Optimal working set of bounds for solution (xOpt,yOpt). \n - (If a null pointer is passed, all bounds are assumed inactive!) */ - const char* const R_file /**< Name of the file where a pre-computed (upper triangular) Cholesky factor - of the Hessian matrix is stored. \n - (If a null pointer is passed, Cholesky decomposition is computed internally!) */ - ); - - -/** Solves an initialised QP sequence using the online active set strategy. - * By default, QP solution is started from previous solution. - * - * Note: This function internally calls solveQP/solveRegularisedQP - * for solving an initialised QP! - * - * \return SUCCESSFUL_RETURN \n - RET_MAX_NWSR_REACHED \n - RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n - RET_HOTSTART_FAILED \n - RET_SHIFT_DETERMINATION_FAILED \n - RET_STEPDIRECTION_DETERMINATION_FAILED \n - RET_STEPLENGTH_DETERMINATION_FAILED \n - RET_HOMOTOPY_STEP_FAILED \n - RET_HOTSTART_STOPPED_INFEASIBILITY \n - RET_HOTSTART_STOPPED_UNBOUNDEDNESS */ -returnValue QProblemB_hotstart( QProblemB* _THIS, - const real_t* const g_new, /**< Gradient of neighbouring QP to be solved. */ - const real_t* const lb_new, /**< Lower bounds of neighbouring QP to be solved. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const ub_new, /**< Upper bounds of neighbouring QP to be solved. \n - If no upper bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations; \n - Output: Number of performed working set recalculations. */ - real_t* const cputime /**< Input: Maximum CPU time allowed for QP solution. \n - Output: CPU time spent for QP solution (or to perform nWSR iterations). */ - ); - -/** Solves an initialised QP sequence using the online active set strategy, - * where QP data is read from files. QP solution is started from previous solution. - * - * Note: This function internally calls solveQP/solveRegularisedQP - * for solving an initialised QP! - * - * \return SUCCESSFUL_RETURN \n - RET_MAX_NWSR_REACHED \n - RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n - RET_HOTSTART_FAILED \n - RET_SHIFT_DETERMINATION_FAILED \n - RET_STEPDIRECTION_DETERMINATION_FAILED \n - RET_STEPLENGTH_DETERMINATION_FAILED \n - RET_HOMOTOPY_STEP_FAILED \n - RET_HOTSTART_STOPPED_INFEASIBILITY \n - RET_HOTSTART_STOPPED_UNBOUNDEDNESS \n - RET_UNABLE_TO_READ_FILE \n - RET_INVALID_ARGUMENTS */ -returnValue QProblemB_hotstartF( QProblemB* _THIS, - const char* const g_file, /**< Name of file where gradient, of neighbouring QP to be solved, is stored. */ - const char* const lb_file, /**< Name of file where lower bounds, of neighbouring QP to be solved, is stored. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const char* const ub_file, /**< Name of file where upper bounds, of neighbouring QP to be solved, is stored. \n - If no upper bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations; \n - Output: Number of performed working set recalculations. */ - real_t* const cputime /**< Input: Maximum CPU time allowed for QP solution. \n - Output: CPU time spent for QP solution (or to perform nWSR iterations). */ - ); - -/** Solves an initialised QP sequence using the online active set strategy. - * By default, QP solution is started from previous solution. If a guess - * for the working set is provided, an initialised homotopy is performed. - * - * Note: This function internally calls solveQP/solveRegularisedQP - * for solving an initialised QP! - * - * \return SUCCESSFUL_RETURN \n - RET_MAX_NWSR_REACHED \n - RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n - RET_HOTSTART_FAILED \n - RET_SHIFT_DETERMINATION_FAILED \n - RET_STEPDIRECTION_DETERMINATION_FAILED \n - RET_STEPLENGTH_DETERMINATION_FAILED \n - RET_HOMOTOPY_STEP_FAILED \n - RET_HOTSTART_STOPPED_INFEASIBILITY \n - RET_HOTSTART_STOPPED_UNBOUNDEDNESS \n - RET_SETUP_AUXILIARYQP_FAILED */ -returnValue QProblemB_hotstartW( QProblemB* _THIS, - const real_t* const g_new, /**< Gradient of neighbouring QP to be solved. */ - const real_t* const lb_new, /**< Lower bounds of neighbouring QP to be solved. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const ub_new, /**< Upper bounds of neighbouring QP to be solved. \n - If no upper bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations; \n - Output: Number of performed working set recalculations. */ - real_t* const cputime, /**< Input: Maximum CPU time allowed for QP solution. \n - Output: CPU time spent for QP solution (or to perform nWSR iterations). */ - Bounds* const guessedBounds /**< Optimal working set of bounds for solution (xOpt,yOpt). \n - (If a null pointer is passed, the previous working set is kept!) */ - ); - -/** Solves an initialised QP sequence using the online active set strategy, - * where QP data is read from files. - * By default, QP solution is started from previous solution. If a guess - * for the working set is provided, an initialised homotopy is performed. - * - * Note: This function internally calls solveQP/solveRegularisedQP - * for solving an initialised QP! - * - * \return SUCCESSFUL_RETURN \n - RET_MAX_NWSR_REACHED \n - RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n - RET_HOTSTART_FAILED \n - RET_SHIFT_DETERMINATION_FAILED \n - RET_STEPDIRECTION_DETERMINATION_FAILED \n - RET_STEPLENGTH_DETERMINATION_FAILED \n - RET_HOMOTOPY_STEP_FAILED \n - RET_HOTSTART_STOPPED_INFEASIBILITY \n - RET_HOTSTART_STOPPED_UNBOUNDEDNESS \n - RET_UNABLE_TO_READ_FILE \n - RET_INVALID_ARGUMENTS \n - RET_SETUP_AUXILIARYQP_FAILED */ -returnValue QProblemB_hotstartFW( QProblemB* _THIS, - const char* const g_file, /**< Name of file where gradient, of neighbouring QP to be solved, is stored. */ - const char* const lb_file, /**< Name of file where lower bounds, of neighbouring QP to be solved, is stored. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const char* const ub_file, /**< Name of file where upper bounds, of neighbouring QP to be solved, is stored. \n - If no upper bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations; \n - Output: Number of performed working set recalculations. */ - real_t* const cputime, /**< Input: Maximum CPU time allowed for QP solution. \n - Output: CPU time spent for QP solution (or to perform nWSR iterations). */ - Bounds* const guessedBounds /**< Optimal working set of bounds for solution (xOpt,yOpt). \n - (If a null pointer is passed, the previous working set is kept!) */ - ); - - -/** Writes a vector with the state of the working set - * \return SUCCESSFUL_RETURN \n - * RET_INVALID_ARGUMENTS */ -returnValue QProblemB_getWorkingSet( QProblemB* _THIS, - real_t* workingSet /** Output: array containing state of the working set. */ - ); - -/** Writes a vector with the state of the working set of bounds - * \return SUCCESSFUL_RETURN \n - * RET_INVALID_ARGUMENTS */ -returnValue QProblemB_getWorkingSetBounds( QProblemB* _THIS, - real_t* workingSetB /** Output: array containing state of the working set of bounds. */ - ); - -/** Writes a vector with the state of the working set of constraints - * \return SUCCESSFUL_RETURN \n - * RET_INVALID_ARGUMENTS */ -returnValue QProblemB_getWorkingSetConstraints( QProblemB* _THIS, - real_t* workingSetC /** Output: array containing state of the working set of constraints. */ - ); - - -/** Returns current bounds object of the QP (deep copy). - * \return SUCCESSFUL_RETURN \n - RET_QPOBJECT_NOT_SETUP */ -static inline returnValue QProblemB_getBounds( QProblemB* _THIS, - Bounds* _bounds /** Output: Bounds object. */ - ); - - -/** Returns the number of variables. - * \return Number of variables. */ -static inline int QProblemB_getNV( QProblemB* _THIS ); - -/** Returns the number of free variables. - * \return Number of free variables. */ -static inline int QProblemB_getNFR( QProblemB* _THIS ); - -/** Returns the number of fixed variables. - * \return Number of fixed variables. */ -static inline int QProblemB_getNFX( QProblemB* _THIS ); - -/** Returns the number of implicitly fixed variables. - * \return Number of implicitly fixed variables. */ -static inline int QProblemB_getNFV( QProblemB* _THIS ); - -/** Returns the dimension of null space. - * \return Dimension of null space. */ -int QProblemB_getNZ( QProblemB* _THIS ); - - -/** Returns the optimal objective function value. - * \return finite value: Optimal objective function value (QP was solved) \n - +infinity: QP was not yet solved */ -real_t QProblemB_getObjVal( QProblemB* _THIS ); - -/** Returns the objective function value at an arbitrary point x. - * \return Objective function value at point x */ -real_t QProblemB_getObjValX( QProblemB* _THIS, - const real_t* const _x /**< Point at which the objective function shall be evaluated. */ - ); - -/** Returns the primal solution vector. - * \return SUCCESSFUL_RETURN \n - RET_QP_NOT_SOLVED */ -returnValue QProblemB_getPrimalSolution( QProblemB* _THIS, - real_t* const xOpt /**< Output: Primal solution vector (if QP has been solved). */ - ); - -/** Returns the dual solution vector. - * \return SUCCESSFUL_RETURN \n - RET_QP_NOT_SOLVED */ -returnValue QProblemB_getDualSolution( QProblemB* _THIS, - real_t* const yOpt /**< Output: Dual solution vector (if QP has been solved). */ - ); - - -/** Returns status of the solution process. - * \return Status of solution process. */ -static inline QProblemStatus QProblemB_getStatus( QProblemB* _THIS ); - - -/** Returns if the QProblem object is initialised. - * \return BT_TRUE: QProblemB initialised \n - BT_FALSE: QProblemB not initialised */ -static inline BooleanType QProblemB_isInitialised( QProblemB* _THIS ); - -/** Returns if the QP has been solved. - * \return BT_TRUE: QProblemB solved \n - BT_FALSE: QProblemB not solved */ -static inline BooleanType QProblemB_isSolved( QProblemB* _THIS ); - -/** Returns if the QP is infeasible. - * \return BT_TRUE: QP infeasible \n - BT_FALSE: QP feasible (or not known to be infeasible!) */ -static inline BooleanType QProblemB_isInfeasible( QProblemB* _THIS ); - -/** Returns if the QP is unbounded. - * \return BT_TRUE: QP unbounded \n - BT_FALSE: QP unbounded (or not known to be unbounded!) */ -static inline BooleanType QProblemB_isUnbounded( QProblemB* _THIS ); - - -/** Returns Hessian type flag (type is not determined due to _THIS call!). - * \return Hessian type. */ -static inline HessianType QProblemB_getHessianType( QProblemB* _THIS ); - -/** Changes the print level. - * \return SUCCESSFUL_RETURN */ -static inline returnValue QProblemB_setHessianType( QProblemB* _THIS, - HessianType _hessianType /**< New Hessian type. */ - ); - -/** Returns if the QP has been internally regularised. - * \return BT_TRUE: Hessian is internally regularised for QP solution \n - BT_FALSE: No internal Hessian regularisation is used for QP solution */ -static inline BooleanType QProblemB_usingRegularisation( QProblemB* _THIS ); - -/** Returns current options struct. - * \return Current options struct. */ -static inline Options QProblemB_getOptions( QProblemB* _THIS ); - -/** Overrides current options with given ones. - * \return SUCCESSFUL_RETURN */ -static inline returnValue QProblemB_setOptions( QProblemB* _THIS, - Options _options /**< New options. */ - ); - -/** Returns the print level. - * \return Print level. */ -static inline PrintLevel QProblemB_getPrintLevel( QProblemB* _THIS ); - -/** Changes the print level. - * \return SUCCESSFUL_RETURN */ -returnValue QProblemB_setPrintLevel( QProblemB* _THIS, - PrintLevel _printlevel /**< New print level. */ - ); - -/** Returns the current number of QP problems solved. - * \return Number of QP problems solved. */ -static inline unsigned int QProblemB_getCount( QProblemB* _THIS ); - -/** Resets QP problem counter (to zero). - * \return SUCCESSFUL_RETURN. */ -static inline returnValue QProblemB_resetCounter( QProblemB* _THIS ); - - -/** Prints concise list of properties of the current QP. - * \return SUCCESSFUL_RETURN \n */ -returnValue QProblemB_printProperties( QProblemB* _THIS ); - -/** Prints a list of all options and their current values. - * \return SUCCESSFUL_RETURN \n */ -returnValue QProblemB_printOptions( QProblemB* _THIS ); - - -/** If Hessian type has been set by the user, nothing is done. - * Otherwise the Hessian type is set to HST_IDENTITY, HST_ZERO, or - * HST_POSDEF (default), respectively. - * \return SUCCESSFUL_RETURN \n - RET_HESSIAN_INDEFINITE */ -returnValue QProblemB_determineHessianType( QProblemB* _THIS ); - -/** Determines type of existing constraints and bounds (i.e. implicitly fixed, unbounded etc.). - * \return SUCCESSFUL_RETURN \n - RET_SETUPSUBJECTTOTYPE_FAILED */ -returnValue QProblemB_setupSubjectToType( QProblemB* _THIS ); - -/** Determines type of new constraints and bounds (i.e. implicitly fixed, unbounded etc.). - * \return SUCCESSFUL_RETURN \n - RET_SETUPSUBJECTTOTYPE_FAILED */ -returnValue QProblemB_setupSubjectToTypeNew( QProblemB* _THIS, - const real_t* const lb_new, /**< New lower bounds. */ - const real_t* const ub_new /**< New upper bounds. */ - ); - -/** Computes the Cholesky decomposition of the (simply projected) Hessian - * (i.e. R^T*R = Z^T*H*Z). It only works in the case where Z is a simple - * projection matrix! - * Note: If Hessian turns out not to be positive definite, the Hessian type - * is set to HST_SEMIDEF accordingly. - * \return SUCCESSFUL_RETURN \n - * RET_HESSIAN_NOT_SPD \n - * RET_INDEXLIST_CORRUPTED */ -returnValue QProblemB_computeCholesky( QProblemB* _THIS ); - -/** Computes initial Cholesky decomposition of the projected Hessian making - * use of the function setupCholeskyDecomposition() or setupCholeskyDecompositionProjected(). - * \return SUCCESSFUL_RETURN \n - * RET_HESSIAN_NOT_SPD \n - * RET_INDEXLIST_CORRUPTED */ -returnValue QProblemB_setupInitialCholesky( QProblemB* _THIS ); - - -/** Obtains the desired working set for the auxiliary initial QP in - * accordance with the user specifications - * \return SUCCESSFUL_RETURN \n - RET_OBTAINING_WORKINGSET_FAILED \n - RET_INVALID_ARGUMENTS */ -returnValue QProblemB_obtainAuxiliaryWorkingSet( QProblemB* _THIS, - const real_t* const xOpt, /**< Optimal primal solution vector. - * If a NULL pointer is passed, all entries are assumed to be zero. */ - const real_t* const yOpt, /**< Optimal dual solution vector. - * If a NULL pointer is passed, all entries are assumed to be zero. */ - Bounds* const guessedBounds, /**< Guessed working set for solution (xOpt,yOpt). */ - Bounds* auxiliaryBounds /**< Input: Allocated bound object. \n - * Ouput: Working set for auxiliary QP. */ - ); - -/** Decides if lower bounds are smaller than upper bounds - * - * \return SUCCESSFUL_RETURN \n - * RET_QP_INFEASIBLE */ -returnValue QProblemB_areBoundsConsistent( QProblemB* _THIS, - const real_t* const lb, /**< Vector of lower bounds*/ - const real_t* const ub /**< Vector of upper bounds*/ - ); - -/** Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix. - * \return SUCCESSFUL_RETURN \n - RET_DIV_BY_ZERO */ -returnValue QProblemB_backsolveR( QProblemB* _THIS, - const real_t* const b, /**< Right hand side vector. */ - BooleanType transposed, /**< Indicates if the transposed system shall be solved. */ - real_t* const a /**< Output: Solution vector */ - ); - -/** Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix. \n - * Special variant for the case that _THIS function is called from within "removeBound()". - * \return SUCCESSFUL_RETURN \n - RET_DIV_BY_ZERO */ -returnValue QProblemB_backsolveRrem( QProblemB* _THIS, - const real_t* const b, /**< Right hand side vector. */ - BooleanType transposed, /**< Indicates if the transposed system shall be solved. */ - BooleanType removingBound, /**< Indicates if function is called from "removeBound()". */ - real_t* const a /**< Output: Solution vector */ - ); - - -/** Determines step direction of the shift of the QP data. - * \return SUCCESSFUL_RETURN */ -returnValue QProblemB_determineDataShift( QProblemB* _THIS, - const real_t* const g_new, /**< New gradient vector. */ - const real_t* const lb_new, /**< New lower bounds. */ - const real_t* const ub_new, /**< New upper bounds. */ - real_t* const delta_g, /**< Output: Step direction of gradient vector. */ - real_t* const delta_lb, /**< Output: Step direction of lower bounds. */ - real_t* const delta_ub, /**< Output: Step direction of upper bounds. */ - BooleanType* Delta_bB_isZero/**< Output: Indicates if active bounds are to be shifted. */ - ); - - -/** Sets up internal QP data. - * \return SUCCESSFUL_RETURN \n - RET_INVALID_ARGUMENTS */ -returnValue QProblemB_setupQPdataM( QProblemB* _THIS, - DenseMatrix *_H, /**< Hessian matrix.*/ - const real_t* const _g, /**< Gradient vector. */ - const real_t* const _lb, /**< Lower bounds (on variables). \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const _ub /**< Upper bounds (on variables). \n - If no upper bounds exist, a NULL pointer can be passed. */ - ); - -/** Sets up internal QP data. If the current Hessian is trivial - * (i.e. HST_ZERO or HST_IDENTITY) but a non-trivial one is given, - * memory for Hessian is allocated and it is set to the given one. - * \return SUCCESSFUL_RETURN \n - RET_INVALID_ARGUMENTS \n - RET_NO_HESSIAN_SPECIFIED */ -returnValue QProblemB_setupQPdata( QProblemB* _THIS, - real_t* const _H, /**< Hessian matrix. \n - If Hessian matrix is trivial,a NULL pointer can be passed. */ - const real_t* const _g, /**< Gradient vector. */ - const real_t* const _lb, /**< Lower bounds (on variables). \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const _ub /**< Upper bounds (on variables). \n - If no upper bounds exist, a NULL pointer can be passed. */ - ); - -/** Sets up internal QP data by loading it from files. If the current Hessian - * is trivial (i.e. HST_ZERO or HST_IDENTITY) but a non-trivial one is given, - * memory for Hessian is allocated and it is set to the given one. - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_OPEN_FILE \n - RET_UNABLE_TO_READ_FILE \n - RET_INVALID_ARGUMENTS \n - RET_NO_HESSIAN_SPECIFIED */ -returnValue QProblemB_setupQPdataFromFile( QProblemB* _THIS, - const char* const H_file, /**< Name of file where Hessian matrix, of neighbouring QP to be solved, is stored. \n - If Hessian matrix is trivial,a NULL pointer can be passed. */ - const char* const g_file, /**< Name of file where gradient, of neighbouring QP to be solved, is stored. */ - const char* const lb_file, /**< Name of file where lower bounds, of neighbouring QP to be solved, is stored. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const char* const ub_file /**< Name of file where upper bounds, of neighbouring QP to be solved, is stored. \n - If no upper bounds exist, a NULL pointer can be passed. */ - ); - -/** Loads new QP vectors from files (internal members are not affected!). - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_OPEN_FILE \n - RET_UNABLE_TO_READ_FILE \n - RET_INVALID_ARGUMENTS */ -returnValue QProblemB_loadQPvectorsFromFile( QProblemB* _THIS, - const char* const g_file, /**< Name of file where gradient, of neighbouring QP to be solved, is stored. */ - const char* const lb_file, /**< Name of file where lower bounds, of neighbouring QP to be solved, is stored. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const char* const ub_file, /**< Name of file where upper bounds, of neighbouring QP to be solved, is stored. \n - If no upper bounds exist, a NULL pointer can be passed. */ - real_t* const g_new, /**< Output: Gradient of neighbouring QP to be solved. */ - real_t* const lb_new, /**< Output: Lower bounds of neighbouring QP to be solved */ - real_t* const ub_new /**< Output: Upper bounds of neighbouring QP to be solved */ - ); - - -/** Sets internal infeasibility flag and throws given error in case the far bound - * strategy is not enabled (as QP might actually not be infeasible in _THIS case). - * \return RET_HOTSTART_STOPPED_INFEASIBILITY \n - RET_ENSURELI_FAILED_CYCLING \n - RET_ENSURELI_FAILED_NOINDEX */ -returnValue QProblemB_setInfeasibilityFlag( QProblemB* _THIS, - returnValue returnvalue, /**< Returnvalue to be tunneled. */ - BooleanType doThrowError /**< Flag forcing to throw an error. */ - ); - - -/** Determines if next QP iteration can be performed within given CPU time limit. - * \return BT_TRUE: CPU time limit is exceeded, stop QP solution. \n - BT_FALSE: Sufficient CPU time for next QP iteration. */ -BooleanType QProblemB_isCPUtimeLimitExceeded( QProblemB* _THIS, - const real_t* const cputime, /**< Maximum CPU time allowed for QP solution. */ - real_t starttime, /**< Start time of current QP solution. */ - int nWSR /**< Number of working set recalculations performed so far. */ - ); - - -/** Regularise Hessian matrix by adding a scaled identity matrix to it. - * \return SUCCESSFUL_RETURN \n - RET_HESSIAN_ALREADY_REGULARISED */ -returnValue QProblemB_regulariseHessian( QProblemB* _THIS ); - - -/** Sets Hessian matrix of the QP. - * \return SUCCESSFUL_RETURN */ -static inline returnValue QProblemB_setHM( QProblemB* _THIS, - DenseMatrix* H_new /**< New Hessian matrix. */ - ); - -/** Sets dense Hessian matrix of the QP. - * If a null pointer is passed and - * a) hessianType is HST_IDENTITY, nothing is done, - * b) hessianType is not HST_IDENTITY, Hessian matrix is set to zero. - * \return SUCCESSFUL_RETURN */ -static inline returnValue QProblemB_setH( QProblemB* _THIS, - real_t* const H_new /**< New dense Hessian matrix (with correct dimension!). */ - ); - -/** Changes gradient vector of the QP. - * \return SUCCESSFUL_RETURN \n - * RET_INVALID_ARGUMENTS */ -static inline returnValue QProblemB_setG( QProblemB* _THIS, - const real_t* const g_new /**< New gradient vector (with correct dimension!). */ - ); - -/** Changes lower bound vector of the QP. - * \return SUCCESSFUL_RETURN \n - * RET_QPOBJECT_NOT_SETUP */ -static inline returnValue QProblemB_setLB( QProblemB* _THIS, - const real_t* const lb_new /**< New lower bound vector (with correct dimension!). */ - ); - -/** Changes single entry of lower bound vector of the QP. - * \return SUCCESSFUL_RETURN \n - * RET_QPOBJECT_NOT_SETUP \n - * RET_INDEX_OUT_OF_BOUNDS */ -static inline returnValue QProblemB_setLBn( QProblemB* _THIS, - int number, /**< Number of entry to be changed. */ - real_t value /**< New value for entry of lower bound vector. */ - ); - -/** Changes upper bound vector of the QP. - * \return SUCCESSFUL_RETURN \n - * RET_QPOBJECT_NOT_SETUP */ -static inline returnValue QProblemB_setUB( QProblemB* _THIS, - const real_t* const ub_new /**< New upper bound vector (with correct dimension!). */ - ); - -/** Changes single entry of upper bound vector of the QP. - * \return SUCCESSFUL_RETURN \n - * RET_QPOBJECT_NOT_SETUP \n - * RET_INDEX_OUT_OF_BOUNDS */ -static inline returnValue QProblemB_setUBn( QProblemB* _THIS, - int number, /**< Number of entry to be changed. */ - real_t value /**< New value for entry of upper bound vector. */ - ); - - -/** Computes parameters for the Givens matrix G for which [x,y]*G = [z,0] - * \return SUCCESSFUL_RETURN */ -static inline void QProblemB_computeGivens( real_t xold, /**< Matrix entry to be normalised. */ - real_t yold, /**< Matrix entry to be annihilated. */ - real_t* xnew, /**< Output: Normalised matrix entry. */ - real_t* ynew, /**< Output: Annihilated matrix entry. */ - real_t* c, /**< Output: Cosine entry of Givens matrix. */ - real_t* s /**< Output: Sine entry of Givens matrix. */ - ); - -/** Applies Givens matrix determined by c and s (cf. computeGivens). - * \return SUCCESSFUL_RETURN */ -static inline void QProblemB_applyGivens( real_t c, /**< Cosine entry of Givens matrix. */ - real_t s, /**< Sine entry of Givens matrix. */ - real_t nu, /**< Further factor: s/(1+c). */ - real_t xold, /**< Matrix entry to be transformed corresponding to - * the normalised entry of the original matrix. */ - real_t yold, /**< Matrix entry to be transformed corresponding to - * the annihilated entry of the original matrix. */ - real_t* xnew, /**< Output: Transformed matrix entry corresponding to - * the normalised entry of the original matrix. */ - real_t* ynew /**< Output: Transformed matrix entry corresponding to - * the annihilated entry of the original matrix. */ - ); - - - -/** Compute relative length of homotopy in data space for termination - * criterion. - * \return Relative length in data space. */ -real_t QProblemB_getRelativeHomotopyLength( QProblemB* _THIS, - const real_t* const g_new, /**< Final gradient. */ - const real_t* const lb_new, /**< Final lower variable bounds. */ - const real_t* const ub_new /**< Final upper variable bounds. */ - ); - -/** Ramping Strategy to avoid ties. Modifies homotopy start without - * changing current active set. - * \return SUCCESSFUL_RETURN */ -returnValue QProblemB_performRamping( QProblemB* _THIS ); - - -/** ... */ -returnValue QProblemB_updateFarBounds( QProblemB* _THIS, - real_t curFarBound, /**< ... */ - int nRamp, /**< ... */ - const real_t* const lb_new, /**< ... */ - real_t* const lb_new_far, /**< ... */ - const real_t* const ub_new, /**< ... */ - real_t* const ub_new_far /**< ... */ - ); - - - -/** Performs robustified ratio test yield the maximum possible step length - * along the homotopy path. - * \return SUCCESSFUL_RETURN */ -returnValue QProblemB_performRatioTestB( QProblemB* _THIS, - int nIdx, /**< Number of ratios to be checked. */ - const int* const idxList, /**< Array containing the indices of all ratios to be checked. */ - Bounds* const subjectTo, /**< Bound object corresponding to ratios to be checked. */ - const real_t* const num, /**< Array containing all numerators for performing the ratio test. */ - const real_t* const den, /**< Array containing all denominators for performing the ratio test. */ - real_t epsNum, /**< Numerator tolerance. */ - real_t epsDen, /**< Denominator tolerance. */ - real_t* t, /**< Output: Maximum possible step length along the homotopy path. */ - int* BC_idx /**< Output: Index of blocking constraint. */ - ); - -/** Checks whether given ratio is blocking, i.e. limits the maximum step length - * along the homotopy path to a value lower than given one. - * \return SUCCESSFUL_RETURN */ -static inline BooleanType QProblemB_isBlocking( QProblemB* _THIS, - real_t num, /**< Numerator for performing the ratio test. */ - real_t den, /**< Denominator for performing the ratio test. */ - real_t epsNum, /**< Numerator tolerance. */ - real_t epsDen, /**< Denominator tolerance. */ - real_t* t /**< Input: Current maximum step length along the homotopy path, - * Output: Updated maximum possible step length along the homotopy path. */ - ); - - -/** Solves a QProblemB whose QP data is assumed to be stored in the member variables. - * A guess for its primal/dual optimal solution vectors and the corresponding - * optimal working set can be provided. - * Note: This function is internally called by all init functions! - * \return SUCCESSFUL_RETURN \n - RET_INIT_FAILED \n - RET_INIT_FAILED_CHOLESKY \n - RET_INIT_FAILED_HOTSTART \n - RET_INIT_FAILED_INFEASIBILITY \n - RET_INIT_FAILED_UNBOUNDEDNESS \n - RET_MAX_NWSR_REACHED */ -returnValue QProblemB_solveInitialQP( QProblemB* _THIS, - const real_t* const xOpt, /**< Optimal primal solution vector.*/ - const real_t* const yOpt, /**< Optimal dual solution vector. */ - Bounds* const guessedBounds, /**< Optimal working set of bounds for solution (xOpt,yOpt). */ - const real_t* const _R, /**< Pre-computed (upper triangular) Cholesky factor of Hessian matrix. */ - int* nWSR, /**< Input: Maximum number of working set recalculations; \n - * Output: Number of performed working set recalculations. */ - real_t* const cputime /**< Input: Maximum CPU time allowed for QP solution. \n - * Output: CPU time spent for QP solution (or to perform nWSR iterations). */ - ); - -/** Solves an initialised QProblemB using online active set strategy. - * Note: This function is internally called by all hotstart functions! - * \return SUCCESSFUL_RETURN \n - RET_MAX_NWSR_REACHED \n - RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n - RET_HOTSTART_FAILED \n - RET_SHIFT_DETERMINATION_FAILED \n - RET_STEPDIRECTION_DETERMINATION_FAILED \n - RET_STEPLENGTH_DETERMINATION_FAILED \n - RET_HOMOTOPY_STEP_FAILED \n - RET_HOTSTART_STOPPED_INFEASIBILITY \n - RET_HOTSTART_STOPPED_UNBOUNDEDNESS */ -returnValue QProblemB_solveQP( QProblemB* _THIS, - const real_t* const g_new, /**< Gradient of neighbouring QP to be solved. */ - const real_t* const lb_new, /**< Lower bounds of neighbouring QP to be solved. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const ub_new, /**< Upper bounds of neighbouring QP to be solved. \n - If no upper bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations; \n - Output: Number of performed working set recalculations. */ - real_t* const cputime, /**< Input: Maximum CPU time allowed for QP solution. \n - Output: CPU time spent for QP solution (or to perform nWSR iterations). */ - int nWSRperformed, /**< Number of working set recalculations already performed to solve - this QP within previous solveQP() calls. This number is - always zero, except for successive calls from solveRegularisedQP() - or when using the far bound strategy. */ - BooleanType isFirstCall /**< Indicating whether this is the first call for current QP. */ - ); - - -/** Solves an initialised QProblemB using online active set strategy. - * Note: This function is internally called by all hotstart functions! - * \return SUCCESSFUL_RETURN \n - RET_MAX_NWSR_REACHED \n - RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n - RET_HOTSTART_FAILED \n - RET_SHIFT_DETERMINATION_FAILED \n - RET_STEPDIRECTION_DETERMINATION_FAILED \n - RET_STEPLENGTH_DETERMINATION_FAILED \n - RET_HOMOTOPY_STEP_FAILED \n - RET_HOTSTART_STOPPED_INFEASIBILITY \n - RET_HOTSTART_STOPPED_UNBOUNDEDNESS */ -returnValue QProblemB_solveRegularisedQP( QProblemB* _THIS, - const real_t* const g_new, /**< Gradient of neighbouring QP to be solved. */ - const real_t* const lb_new, /**< Lower bounds of neighbouring QP to be solved. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const ub_new, /**< Upper bounds of neighbouring QP to be solved. \n - If no upper bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations; \n - Output: Number of performed working set recalculations. */ - real_t* const cputime, /**< Input: Maximum CPU time allowed for QP solution. \n - Output: CPU time spent for QP solution (or to perform nWSR iterations). */ - int nWSRperformed, /**< Number of working set recalculations already performed to solve - this QP within previous solveRegularisedQP() calls. This number is - always zero, except for successive calls when using the far bound strategy. */ - BooleanType isFirstCall /**< Indicating whether this is the first call for current QP. */ - ); - - -/** Sets up bound data structure according to auxiliaryBounds. - * (If the working set shall be setup afresh, make sure that - * bounds data structure has been resetted!) - * \return SUCCESSFUL_RETURN \n - RET_SETUP_WORKINGSET_FAILED \n - RET_INVALID_ARGUMENTS \n - RET_UNKNOWN_BUG */ -returnValue QProblemB_setupAuxiliaryWorkingSet( QProblemB* _THIS, - Bounds* const auxiliaryBounds, /**< Working set for auxiliary QP. */ - BooleanType setupAfresh /**< Flag indicating if given working set shall be - * setup afresh or by updating the current one. */ - ); - -/** Sets up the optimal primal/dual solution of the auxiliary initial QP. - * \return SUCCESSFUL_RETURN */ -returnValue QProblemB_setupAuxiliaryQPsolution( QProblemB* _THIS, - const real_t* const xOpt, /**< Optimal primal solution vector. - * If a NULL pointer is passed, all entries are set to zero. */ - const real_t* const yOpt /**< Optimal dual solution vector. - * If a NULL pointer is passed, all entries are set to zero. */ - ); - -/** Sets up gradient of the auxiliary initial QP for given - * optimal primal/dual solution and given initial working set - * (assumes that members X, Y and BOUNDS have already been (ialised!). - * \return SUCCESSFUL_RETURN */ -returnValue QProblemB_setupAuxiliaryQPgradient( QProblemB* _THIS ); - -/** Sets up bounds of the auxiliary initial QP for given - * optimal primal/dual solution and given initial working set - * (assumes that members X, Y and BOUNDS have already been initialised!). - * \return SUCCESSFUL_RETURN \n - RET_UNKNOWN_BUG */ -returnValue QProblemB_setupAuxiliaryQPbounds( QProblemB* _THIS, - BooleanType useRelaxation /**< Flag indicating if inactive bounds shall be relaxed. */ - ); - - -/** Updates QP vectors, working sets and internal data structures in order to - start from an optimal solution corresponding to initial guesses of the working - set for bounds - * \return SUCCESSFUL_RETURN \n - * RET_SETUP_AUXILIARYQP_FAILED */ -returnValue QProblemB_setupAuxiliaryQP( QProblemB* _THIS, - Bounds* const guessedBounds /**< Initial guess for working set of bounds. */ - ); - -/** Determines step direction of the homotopy path. - * \return SUCCESSFUL_RETURN \n - RET_STEPDIRECTION_FAILED_CHOLESKY */ -returnValue QProblemB_determineStepDirection( QProblemB* _THIS, - const real_t* const delta_g, /**< Step direction of gradient vector. */ - const real_t* const delta_lb, /**< Step direction of lower bounds. */ - const real_t* const delta_ub, /**< Step direction of upper bounds. */ - BooleanType Delta_bB_isZero, /**< Indicates if active bounds are to be shifted. */ - real_t* const delta_xFX, /**< Output: Primal homotopy step direction of fixed variables. */ - real_t* const delta_xFR, /**< Output: Primal homotopy step direction of free variables. */ - real_t* const delta_yFX /**< Output: Dual homotopy step direction of fixed variables' multiplier. */ - ); - -/** Determines the maximum possible step length along the homotopy path - * and performs _THIS step (without changing working set). - * \return SUCCESSFUL_RETURN \n - * RET_QP_INFEASIBLE \n - */ -returnValue QProblemB_performStep( QProblemB* _THIS, - const real_t* const delta_g, /**< Step direction of gradient. */ - const real_t* const delta_lb, /**< Step direction of lower bounds. */ - const real_t* const delta_ub, /**< Step direction of upper bounds. */ - const real_t* const delta_xFX, /**< Primal homotopy step direction of fixed variables. */ - const real_t* const delta_xFR, /**< Primal homotopy step direction of free variables. */ - const real_t* const delta_yFX, /**< Dual homotopy step direction of fixed variables' multiplier. */ - int* BC_idx, /**< Output: Index of blocking constraint. */ - SubjectToStatus* BC_status /**< Output: Status of blocking constraint. */ - ); - -/** Updates active set. - * \return SUCCESSFUL_RETURN \n - RET_REMOVE_FROM_ACTIVESET_FAILED \n - RET_ADD_TO_ACTIVESET_FAILED */ -returnValue QProblemB_changeActiveSet( QProblemB* _THIS, - int BC_idx, /**< Index of blocking constraint. */ - SubjectToStatus BC_status /**< Status of blocking constraint. */ - ); - -/** Drift correction at end of each active set iteration - * \return SUCCESSFUL_RETURN */ -returnValue QProblemB_performDriftCorrection( QProblemB* _THIS ); - -/** Determines if it is more efficient to refactorise the matrices when - * hotstarting or not (i.e. better to update the existing factorisations). - * \return BT_TRUE iff matrices shall be refactorised afresh - */ -BooleanType QProblemB_shallRefactorise( QProblemB* _THIS, - Bounds* const guessedBounds /**< Guessed new working set. */ - ); - - -/** Adds a bound to active set (specialised version for the case where no constraints exist). - * \return SUCCESSFUL_RETURN \n - RET_ADDBOUND_FAILED */ -returnValue QProblemB_addBound( QProblemB* _THIS, - int number, /**< Number of bound to be added to active set. */ - SubjectToStatus B_status, /**< Status of new active bound. */ - BooleanType updateCholesky /**< Flag indicating if Cholesky decomposition shall be updated. */ - ); - -/** Removes a bounds from active set (specialised version for the case where no constraints exist). - * \return SUCCESSFUL_RETURN \n - RET_HESSIAN_NOT_SPD \n - RET_REMOVEBOUND_FAILED */ -returnValue QProblemB_removeBound( QProblemB* _THIS, - int number, /**< Number of bound to be removed from active set. */ - BooleanType updateCholesky /**< Flag indicating if Cholesky decomposition shall be updated. */ - ); - - -/** Prints concise information on the current iteration. - * \return SUCCESSFUL_RETURN \n */ -returnValue QProblemB_printIteration( QProblemB* _THIS, - int iter, /**< Number of current iteration. */ - int BC_idx, /**< Index of blocking bound. */ - SubjectToStatus BC_status, /**< Status of blocking bound. */ - real_t homotopyLength, /**< Current homotopy distance. */ - BooleanType isFirstCall /**< Indicating whether this is the first call for current QP. */ - ); - - - -/* - * g e t B o u n d s - */ -static inline returnValue QProblemB_getBounds( QProblemB* _THIS, Bounds* _bounds ) -{ - int nV = QProblemB_getNV( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - _bounds = _THIS->bounds; - - return SUCCESSFUL_RETURN; -} - - -/* - * g e t N V - */ -static inline int QProblemB_getNV( QProblemB* _THIS ) -{ - return Bounds_getNV( _THIS->bounds ); -} - - -/* - * g e t N F R - */ -static inline int QProblemB_getNFR( QProblemB* _THIS ) -{ - return Bounds_getNFR( _THIS->bounds ); -} - - -/* - * g e t N F X - */ -static inline int QProblemB_getNFX( QProblemB* _THIS ) -{ - return Bounds_getNFX( _THIS->bounds ); -} - - -/* - * g e t N F V - */ -static inline int QProblemB_getNFV( QProblemB* _THIS ) -{ - return Bounds_getNFV( _THIS->bounds ); -} - - -/* - * g e t S t a t u s - */ -static inline QProblemStatus QProblemB_getStatus( QProblemB* _THIS ) -{ - return _THIS->status; -} - - -/* - * i s I n i t i a l i s e d - */ -static inline BooleanType QProblemB_isInitialised( QProblemB* _THIS ) -{ - if ( _THIS->status == QPS_NOTINITIALISED ) - return BT_FALSE; - else - return BT_TRUE; -} - - -/* - * i s S o l v e d - */ -static inline BooleanType QProblemB_isSolved( QProblemB* _THIS ) -{ - if ( _THIS->status == QPS_SOLVED ) - return BT_TRUE; - else - return BT_FALSE; -} - - -/* - * i s I n f e a s i b l e - */ -static inline BooleanType QProblemB_isInfeasible( QProblemB* _THIS ) -{ - return _THIS->infeasible; -} - - -/* - * i s U n b o u n d e d - */ -static inline BooleanType QProblemB_isUnbounded( QProblemB* _THIS ) -{ - return _THIS->unbounded; -} - - -/* - * g e t H e s s i a n T y p e - */ -static inline HessianType QProblemB_getHessianType( QProblemB* _THIS ) -{ - return _THIS->hessianType; -} - - -/* - * s e t H e s s i a n T y p e - */ -static inline returnValue QProblemB_setHessianType( QProblemB* _THIS, HessianType _hessianType ) -{ - _THIS->hessianType = _hessianType; - return SUCCESSFUL_RETURN; -} - - -/* - * u s i n g R e g u l a r i s a t i o n - */ -static inline BooleanType QProblemB_usingRegularisation( QProblemB* _THIS ) -{ - if ( _THIS->regVal > QPOASES_ZERO ) - return BT_TRUE; - else - return BT_FALSE; -} - - -/* - * g e t O p t i o n s - */ -static inline Options QProblemB_getOptions( QProblemB* _THIS ) -{ - return _THIS->options; -} - - -/* - * s e t O p t i o n s - */ -static inline returnValue QProblemB_setOptions( QProblemB* _THIS, - Options _options - ) -{ - OptionsCPY( &_options,&(_THIS->options) ); - Options_ensureConsistency( &(_THIS->options) ); - - QProblemB_setPrintLevel( _THIS,_THIS->options.printLevel ); - - return SUCCESSFUL_RETURN; -} - - -/* - * g e t P r i n t L e v e l - */ -static inline PrintLevel QProblemB_getPrintLevel( QProblemB* _THIS ) -{ - return _THIS->options.printLevel; -} - - - -/* - * g e t C o u n t - */ -static inline unsigned int QProblemB_getCount( QProblemB* _THIS ) -{ - return _THIS->count; -} - - -/* - * r e s e t C o u n t e r - */ -static inline returnValue QProblemB_resetCounter( QProblemB* _THIS ) -{ - _THIS->count = 0; - return SUCCESSFUL_RETURN; -} - - - -/***************************************************************************** - * P R O T E C T E D * - *****************************************************************************/ - - -/* - * s e t H - */ -static inline returnValue QProblemB_setHM( QProblemB* _THIS, DenseMatrix* H_new ) -{ - if ( H_new == 0 ) - return QProblemB_setH( _THIS,(real_t*)0 ); - else - return QProblemB_setH( _THIS,DenseMatrix_getVal(H_new) ); -} - - -/* - * s e t H - */ -static inline returnValue QProblemB_setH( QProblemB* _THIS, real_t* const H_new ) -{ - /* if null pointer is passed, Hessian is set to zero matrix - * (or stays identity matrix) */ - if ( H_new == 0 ) - { - if ( _THIS->hessianType == HST_IDENTITY ) - return SUCCESSFUL_RETURN; - - _THIS->hessianType = HST_ZERO; - - _THIS->H = 0; - } - else - { - DenseMatrixCON( _THIS->H,QProblemB_getNV( _THIS ),QProblemB_getNV( _THIS ),QProblemB_getNV( _THIS ),H_new ); - } - - return SUCCESSFUL_RETURN; -} - - -/* - * s e t G - */ -static inline returnValue QProblemB_setG( QProblemB* _THIS, const real_t* const g_new ) -{ - unsigned int nV = (unsigned int)QProblemB_getNV( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( g_new == 0 ) - return THROWERROR( RET_INVALID_ARGUMENTS ); - - memcpy( _THIS->g,g_new,nV*sizeof(real_t) ); - - return SUCCESSFUL_RETURN; -} - - -/* - * s e t L B - */ -static inline returnValue QProblemB_setLB( QProblemB* _THIS, const real_t* const lb_new ) -{ - unsigned int i; - unsigned int nV = (unsigned int)QProblemB_getNV( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( lb_new != 0 ) - { - memcpy( _THIS->lb,lb_new,nV*sizeof(real_t) ); - } - else - { - /* if no lower bounds are specified, set them to -infinity */ - for( i=0; ilb[i] = -QPOASES_INFTY; - } - - return SUCCESSFUL_RETURN; -} - - -/* - * s e t L B - */ -static inline returnValue QProblemB_setLBn( QProblemB* _THIS, int number, real_t value ) -{ - int nV = QProblemB_getNV( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( ( number >= 0 ) && ( number < nV ) ) - { - _THIS->lb[number] = value; - return SUCCESSFUL_RETURN; - } - else - { - return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); - } -} - - -/* - * s e t U B - */ -static inline returnValue QProblemB_setUB( QProblemB* _THIS, const real_t* const ub_new ) -{ - unsigned int i; - unsigned int nV = (unsigned int)QProblemB_getNV( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( ub_new != 0 ) - { - memcpy( _THIS->ub,ub_new,nV*sizeof(real_t) ); - } - else - { - /* if no upper bounds are specified, set them to infinity */ - for( i=0; iub[i] = QPOASES_INFTY; - } - - return SUCCESSFUL_RETURN; -} - - -/* - * s e t U B - */ -static inline returnValue QProblemB_setUBn( QProblemB* _THIS, int number, real_t value ) -{ - int nV = QProblemB_getNV( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( ( number >= 0 ) && ( number < nV ) ) - { - _THIS->ub[number] = value; - - return SUCCESSFUL_RETURN; - } - else - { - return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); - } -} - - -/* - * c o m p u t e G i v e n s - */ -static inline void QProblemB_computeGivens( real_t xold, real_t yold, - real_t* xnew, real_t* ynew, real_t* c, real_t* s - ) -{ - real_t t, mu; - - if ( fabs( yold ) <= QPOASES_ZERO ) - { - *c = 1.0; - *s = 0.0; - - *xnew = xold; - *ynew = yold; - } - else - { - mu = fabs( xold ); - if ( fabs( yold ) > mu ) - mu = fabs( yold ); - - t = mu * sqrt( (xold/mu)*(xold/mu) + (yold/mu)*(yold/mu) ); - - if ( xold < 0.0 ) - t = -t; - - *c = xold/t; - *s = yold/t; - *xnew = t; - *ynew = 0.0; - } - - return; -} - - -/* - * a p p l y G i v e n s - */ -static inline void QProblemB_applyGivens( real_t c, real_t s, real_t nu, real_t xold, real_t yold, - real_t* xnew, real_t* ynew - ) -{ - #ifdef __USE_THREE_MULTS_GIVENS__ - - /* Givens plane rotation requiring only three multiplications, - * cf. Hammarling, S.: A note on modifications to the givens plane rotation. - * J. Inst. Maths Applics, 13:215-218, 1974. */ - *xnew = xold*c + yold*s; - *ynew = (*xnew+xold)*nu - yold; - - #else - - /* Usual Givens plane rotation requiring four multiplications. */ - *xnew = c*xold + s*yold; - *ynew = -s*xold + c*yold; - - #endif - - return; -} - - -/* - * i s B l o c k i n g - */ -static inline BooleanType QProblemB_isBlocking( QProblemB* _THIS, - real_t num, - real_t den, - real_t epsNum, - real_t epsDen, - real_t* t - ) -{ - if ( ( den >= epsDen ) && ( num >= epsNum ) ) - { - if ( num < (*t)*den ) - return BT_TRUE; - } - - return BT_FALSE; -} - - -END_NAMESPACE_QPOASES - - -#endif /* QPOASES_QPROBLEMB_H */ - - -/* - * end of file - */ diff --git a/third_party/acados/include/qpOASES_e/Types.h b/third_party/acados/include/qpOASES_e/Types.h deleted file mode 100644 index fc042aed82..0000000000 --- a/third_party/acados/include/qpOASES_e/Types.h +++ /dev/null @@ -1,310 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/Types.h - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - * - * Declaration of all non-built-in types (except for classes). - */ - - -#ifndef QPOASES_TYPES_H -#define QPOASES_TYPES_H - -#ifdef USE_ACADOS_TYPES -#include "acados/utils/types.h" -#endif - -/* If your compiler does not support the snprintf() function, - * uncomment the following line and try to compile again. */ -/* #define __NO_SNPRINTF__ */ - - -/* Uncomment the following line for setting the __DSPACE__ flag. */ -/* #define __DSPACE__ */ - -/* Uncomment the following line for setting the __XPCTARGET__ flag. */ -/* #define __XPCTARGET__ */ - - -/* Uncomment the following line for setting the __NO_FMATH__ flag. */ -/* #define __NO_FMATH__ */ - -/* Uncomment the following line to enable debug information. */ -/* #define __DEBUG__ */ - -/* Uncomment the following line to enable suppress any kind of console output. */ -/* #define __SUPPRESSANYOUTPUT__ */ - - -/** Forces to always include all implicitly fixed bounds and all equality constraints - * into the initial working set when setting up an auxiliary QP. */ -#define __ALWAYS_INITIALISE_WITH_ALL_EQUALITIES__ - -/* Uncomment the following line to activate the use of an alternative Givens - * plane rotation requiring only three multiplications. */ -/* #define __USE_THREE_MULTS_GIVENS__ */ - -/* Uncomment the following line to activate the use of single precision arithmetic. */ -/* #define __USE_SINGLE_PRECISION__ */ - -/* The inline keyword is skipped by default as it is not part of the C90 standard. - * However, by uncommenting the following line, use of the inline keyword can be enforced. */ -/* #define __USE_INLINE__ */ - - -/* Work-around for Borland BCC 5.5 compiler. */ -#ifdef __BORLANDC__ -#if __BORLANDC__ < 0x0561 - #define __STDC__ 1 -#endif -#endif - - -/* Work-around for Microsoft compilers. */ -#ifdef _MSC_VER - #define __NO_SNPRINTF__ - #pragma warning( disable : 4061 4100 4250 4514 4996 ) -#endif - - -/* Apply pre-processor settings when using qpOASES within auto-generated code. */ -#ifdef __CODE_GENERATION__ - #define __NO_COPYRIGHT__ - #define __EXTERNAL_DIMENSIONS__ -#endif /* __CODE_GENERATION__ */ - - -/* Avoid using static variables declaration within functions. */ -#ifdef __NO_STATIC__ - #define myStatic -#else - #define myStatic static -#endif /* __NO_STATIC__ */ - - -/* Skip inline keyword if not specified otherwise. */ -#ifndef __USE_INLINE__ - #define inline -#endif - - -/* Avoid any printing on embedded platforms. */ -#if defined(__DSPACE__) || defined(__XPCTARGET__) - #define __SUPPRESSANYOUTPUT__ - #define __NO_SNPRINTF__ -#endif - - -#ifdef __NO_SNPRINTF__ - #if (!defined(_MSC_VER)) || defined(__DSPACE__) || defined(__XPCTARGET__) - /* If snprintf is not available, provide an empty implementation... */ - int snprintf( char* s, size_t n, const char* format, ... ); - #else - /* ... or substitute snprintf by _snprintf for Microsoft compilers. */ - #define snprintf _snprintf - #endif -#endif /* __NO_SNPRINTF__ */ - - -/** Macro for switching on/off the beginning of the qpOASES namespace definition. */ -#define BEGIN_NAMESPACE_QPOASES - -/** Macro for switching on/off the end of the qpOASES namespace definition. */ -#define END_NAMESPACE_QPOASES - -/** Macro for switching on/off the use of the qpOASES namespace. */ -#define USING_NAMESPACE_QPOASES - -/** Macro for switching on/off references to the qpOASES namespace. */ -#define REFER_NAMESPACE_QPOASES /*::*/ - - -/** Macro for accessing the Cholesky factor R. */ -#define RR( I,J ) _THIS->R[(I)+nV*(J)] - -/** Macro for accessing the orthonormal matrix Q of the QT factorisation. */ -#define QQ( I,J ) _THIS->Q[(I)+nV*(J)] - -/** Macro for accessing the triangular matrix T of the QT factorisation. */ -#define TT( I,J ) _THIS->T[(I)*nVC_min+(J)] - - - -BEGIN_NAMESPACE_QPOASES - - -/** Defines real_t for facilitating switching between double and float. */ - -#ifndef USE_ACADOS_TYPES -#ifndef __CODE_GENERATION__ - - #ifdef __USE_SINGLE_PRECISION__ - typedef float real_t; - #else - typedef double real_t; - #endif /* __USE_SINGLE_PRECISION__ */ - -#endif /* __CODE_GENERATION__ */ -#endif /* USE_ACADOS_TYPES */ - -/** Summarises all possible logical values. */ -typedef enum -{ - BT_FALSE = 0, /**< Logical value for "false". */ - BT_TRUE /**< Logical value for "true". */ -} BooleanType; - - -/** Summarises all possible print levels. Print levels are used to describe - * the desired amount of output during runtime of qpOASES. */ -typedef enum -{ - PL_DEBUG_ITER = -2, /**< Full tabular debugging output. */ - PL_TABULAR, /**< Tabular output. */ - PL_NONE, /**< No output. */ - PL_LOW, /**< Print error messages only. */ - PL_MEDIUM, /**< Print error and warning messages as well as concise info messages. */ - PL_HIGH /**< Print all messages with full details. */ -} PrintLevel; - - -/** Defines visibility status of a message. */ -typedef enum -{ - VS_HIDDEN, /**< Message not visible. */ - VS_VISIBLE /**< Message visible. */ -} VisibilityStatus; - - -/** Summarises all possible states of the (S)QProblem(B) object during the -solution process of a QP sequence. */ -typedef enum -{ - QPS_NOTINITIALISED, /**< QProblem object is freshly instantiated or reset. */ - QPS_PREPARINGAUXILIARYQP, /**< An auxiliary problem is currently setup, either at the very beginning - * via an initial homotopy or after changing the QP matrices. */ - QPS_AUXILIARYQPSOLVED, /**< An auxilary problem was solved, either at the very beginning - * via an initial homotopy or after changing the QP matrices. */ - QPS_PERFORMINGHOMOTOPY, /**< A homotopy according to the main idea of the online active - * set strategy is performed. */ - QPS_HOMOTOPYQPSOLVED, /**< An intermediate QP along the homotopy path was solved. */ - QPS_SOLVED /**< The solution of the actual QP was found. */ -} QProblemStatus; - - -/** Summarises all possible types of the QP's Hessian matrix. */ -typedef enum -{ - HST_ZERO, /**< Hessian is zero matrix (i.e. LP formulation). */ - HST_IDENTITY, /**< Hessian is identity matrix. */ - HST_POSDEF, /**< Hessian is (strictly) positive definite. */ - HST_POSDEF_NULLSPACE, /**< Hessian is positive definite on null space of active bounds/constraints. */ - HST_SEMIDEF, /**< Hessian is positive semi-definite. */ - HST_INDEF, /**< Hessian is indefinite. */ - HST_UNKNOWN /**< Hessian type is unknown. */ -} HessianType; - - -/** Summarises all possible types of bounds and constraints. */ -typedef enum -{ - ST_UNBOUNDED, /**< Bound/constraint is unbounded. */ - ST_BOUNDED, /**< Bound/constraint is bounded but not fixed. */ - ST_EQUALITY, /**< Bound/constraint is fixed (implicit equality bound/constraint). */ - ST_DISABLED, /**< Bound/constraint is disabled (i.e. ignored when solving QP). */ - ST_UNKNOWN /**< Type of bound/constraint unknown. */ -} SubjectToType; - - -/** Summarises all possible states of bounds and constraints. */ -typedef enum -{ - ST_LOWER = -1, /**< Bound/constraint is at its lower bound. */ - ST_INACTIVE, /**< Bound/constraint is inactive. */ - ST_UPPER, /**< Bound/constraint is at its upper bound. */ - ST_INFEASIBLE_LOWER, /**< (to be documented) */ - ST_INFEASIBLE_UPPER, /**< (to be documented) */ - ST_UNDEFINED /**< Status of bound/constraint undefined. */ -} SubjectToStatus; - - -/** - * \brief Stores internal information for tabular (debugging) output. - * - * Struct storing internal information for tabular (debugging) output - * when using the (S)QProblem(B) objects. - * - * \author Hans Joachim Ferreau - * \version 3.1embedded - * \date 2013-2015 - */ -typedef struct -{ - int idxAddB; /**< Index of bound that has been added to working set. */ - int idxRemB; /**< Index of bound that has been removed from working set. */ - int idxAddC; /**< Index of constraint that has been added to working set. */ - int idxRemC; /**< Index of constraint that has been removed from working set. */ - int excAddB; /**< Flag indicating whether a bound has been added to working set to keep a regular projected Hessian. */ - int excRemB; /**< Flag indicating whether a bound has been removed from working set to keep a regular projected Hessian. */ - int excAddC; /**< Flag indicating whether a constraint has been added to working set to keep a regular projected Hessian. */ - int excRemC; /**< Flag indicating whether a constraint has been removed from working set to keep a regular projected Hessian. */ -} TabularOutput; - -/** - * \brief Struct containing the variable header for mat file. - * - * Struct storing the header of a variable to be stored in - * Matlab's binary format (using the outdated Level 4 variant - * for simplictiy). - * - * Note, this code snippet has been inspired from the document - * "Matlab(R) MAT-file Format, R2013b" by MathWorks - * - * \author Hans Joachim Ferreau - * \version 3.1embedded - * \date 2013-2015 - */ -typedef struct -{ - long numericFormat; /**< Flag indicating numerical format. */ - long nRows; /**< Number of rows. */ - long nCols; /**< Number of rows. */ - long imaginaryPart; /**< (to be documented) */ - long nCharName; /**< Number of character in name. */ -} MatMatrixHeader; - - -END_NAMESPACE_QPOASES - - -#endif /* QPOASES_TYPES_H */ - - -/* - * end of file - */ diff --git a/third_party/acados/include/qpOASES_e/UnitTesting.h b/third_party/acados/include/qpOASES_e/UnitTesting.h deleted file mode 100644 index dbff201039..0000000000 --- a/third_party/acados/include/qpOASES_e/UnitTesting.h +++ /dev/null @@ -1,79 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/UnitTesting.h - * \author Hans Joachim Ferreau - * \version 3.1embedded - * \date 2014-2015 - * - * Definition of auxiliary functions/macros for unit testing. - */ - - -#ifndef QPOASES_UNIT_TESTING_H -#define QPOASES_UNIT_TESTING_H - - -#ifndef TEST_TOL_FACTOR -#define TEST_TOL_FACTOR 1 -#endif - - -/** Return value for tests that passed. */ -#define TEST_PASSED 0 - -/** Return value for tests that failed. */ -#define TEST_FAILED 1 - -/** Return value for tests that could not run due to missing external data. */ -#define TEST_DATA_NOT_FOUND 99 - - -/** Macro verifying that two numerical values are equal in order to pass unit test. */ -#define QPOASES_TEST_FOR_EQUAL( x,y ) if ( REFER_NAMESPACE_QPOASES isEqual( (x),(y) ) == BT_FALSE ) { return TEST_FAILED; } - -/** Macro verifying that two numerical values are close to each other in order to pass unit test. */ -#define QPOASES_TEST_FOR_NEAR( x,y ) if ( REFER_NAMESPACE_QPOASES getAbs((x)-(y)) / REFER_NAMESPACE_QPOASES getMax( 1.0,REFER_NAMESPACE_QPOASES getAbs(x) ) >= 1e-10 ) { return TEST_FAILED; } - -/** Macro verifying that first quantity is lower or equal than second one in order to pass unit test. */ -#define QPOASES_TEST_FOR_TOL( x,tol ) if ( (x) > (tol)*(TEST_TOL_FACTOR) ) { return TEST_FAILED; } - -/** Macro verifying that a logical expression holds in order to pass unit test. */ -#define QPOASES_TEST_FOR_TRUE( x ) if ( (x) == 0 ) { return TEST_FAILED; } - - - -BEGIN_NAMESPACE_QPOASES - - -END_NAMESPACE_QPOASES - - -#endif /* QPOASES_UNIT_TESTING_H */ - - -/* - * end of file - */ diff --git a/third_party/acados/include/qpOASES_e/Utils.h b/third_party/acados/include/qpOASES_e/Utils.h deleted file mode 100644 index 75e45a56a0..0000000000 --- a/third_party/acados/include/qpOASES_e/Utils.h +++ /dev/null @@ -1,500 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/Utils.h - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - * - * Declaration of some utilities for working with the different QProblem classes. - */ - - -#ifndef QPOASES_UTILS_H -#define QPOASES_UTILS_H - -#include - - -BEGIN_NAMESPACE_QPOASES - - -/** Prints a vector. - * \return SUCCESSFUL_RETURN */ -returnValue qpOASES_printV( const real_t* const v, /**< Vector to be printed. */ - int n /**< Length of vector. */ - ); - -/** Prints a permuted vector. - * \return SUCCESSFUL_RETURN */ -returnValue qpOASES_printPV( const real_t* const v, /**< Vector to be printed. */ - int n, /**< Length of vector. */ - const int* const V_idx /**< Pemutation vector. */ - ); - -/** Prints a named vector. - * \return SUCCESSFUL_RETURN */ -returnValue qpOASES_printNV( const real_t* const v, /**< Vector to be printed. */ - int n, /**< Length of vector. */ - const char* name /** Name of vector. */ - ); - -/** Prints a matrix. - * \return SUCCESSFUL_RETURN */ -returnValue qpOASES_printM( const real_t* const M, /**< Matrix to be printed. */ - int nrow, /**< Row number of matrix. */ - int ncol /**< Column number of matrix. */ - ); - -/** Prints a permuted matrix. - * \return SUCCESSFUL_RETURN */ -returnValue qpOASES_printPM( const real_t* const M, /**< Matrix to be printed. */ - int nrow, /**< Row number of matrix. */ - int ncol , /**< Column number of matrix. */ - const int* const ROW_idx, /**< Row pemutation vector. */ - const int* const COL_idx /**< Column pemutation vector. */ - ); - -/** Prints a named matrix. - * \return SUCCESSFUL_RETURN */ -returnValue qpOASES_printNM( const real_t* const M, /**< Matrix to be printed. */ - int nrow, /**< Row number of matrix. */ - int ncol, /**< Column number of matrix. */ - const char* name /** Name of matrix. */ - ); - -/** Prints an index array. - * \return SUCCESSFUL_RETURN */ -returnValue qpOASES_printI( const int* const _index, /**< Index array to be printed. */ - int n /**< Length of index array. */ - ); - -/** Prints a named index array. - * \return SUCCESSFUL_RETURN */ -returnValue qpOASES_printNI( const int* const _index, /**< Index array to be printed. */ - int n, /**< Length of index array. */ - const char* name /**< Name of index array. */ - ); - - -/** Prints a string to desired output target (useful also for MATLAB output!). - * \return SUCCESSFUL_RETURN */ -returnValue qpOASES_myPrintf( const char* s /**< String to be written. */ - ); - - -/** Prints qpOASES copyright notice. - * \return SUCCESSFUL_RETURN */ -returnValue qpOASES_printCopyrightNotice( ); - - -/** Reads a real_t matrix from file. - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_OPEN_FILE \n - RET_UNABLE_TO_READ_FILE */ -returnValue qpOASES_readFromFileM( real_t* data, /**< Matrix to be read from file. */ - int nrow, /**< Row number of matrix. */ - int ncol, /**< Column number of matrix. */ - const char* datafilename /**< Data file name. */ - ); - -/** Reads a real_t vector from file. - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_OPEN_FILE \n - RET_UNABLE_TO_READ_FILE */ -returnValue qpOASES_readFromFileV( real_t* data, /**< Vector to be read from file. */ - int n, /**< Length of vector. */ - const char* datafilename /**< Data file name. */ - ); - -/** Reads an integer (column) vector from file. - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_OPEN_FILE \n - RET_UNABLE_TO_READ_FILE */ -returnValue qpOASES_readFromFileI( int* data, /**< Vector to be read from file. */ - int n, /**< Length of vector. */ - const char* datafilename /**< Data file name. */ - ); - - -/** Writes a real_t matrix into a file. - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_OPEN_FILE */ -returnValue qpOASES_writeIntoFileM( const real_t* const data, /**< Matrix to be written into file. */ - int nrow, /**< Row number of matrix. */ - int ncol, /**< Column number of matrix. */ - const char* datafilename, /**< Data file name. */ - BooleanType append /**< Indicates if data shall be appended if the file already exists (otherwise it is overwritten). */ - ); - -/** Writes a real_t vector into a file. - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_OPEN_FILE */ -returnValue qpOASES_writeIntoFileV( const real_t* const data, /**< Vector to be written into file. */ - int n, /**< Length of vector. */ - const char* datafilename, /**< Data file name. */ - BooleanType append /**< Indicates if data shall be appended if the file already exists (otherwise it is overwritten). */ - ); - -/** Writes an integer (column) vector into a file. - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_OPEN_FILE */ -returnValue qpOASES_writeIntoFileI( const int* const integer, /**< Integer vector to be written into file. */ - int n, /**< Length of vector. */ - const char* datafilename, /**< Data file name. */ - BooleanType append /**< Indicates if integer shall be appended if the file already exists (otherwise it is overwritten). */ - ); - -/** Writes a real_t matrix/vector into a Matlab binary file. - * \return SUCCESSFUL_RETURN \n - RET_INVALID_ARGUMENTS - RET_UNABLE_TO_WRITE_FILE */ -returnValue qpOASES_writeIntoMatFile( FILE* const matFile, /**< Pointer to Matlab binary file. */ - const real_t* const data, /**< Data to be written into file. */ - int nRows, /**< Row number of matrix. */ - int nCols, /**< Column number of matrix. */ - const char* name /**< Matlab name of matrix/vector to be stored. */ - ); - -/** Writes in integer matrix/vector into a Matlab binary file. - * \return SUCCESSFUL_RETURN \n - RET_INVALID_ARGUMENTS - RET_UNABLE_TO_WRITE_FILE */ -returnValue qpOASES_writeIntoMatFileI( FILE* const matFile, /**< Pointer to Matlab binary file. */ - const int* const data, /**< Data to be written into file. */ - int nRows, /**< Row number of matrix. */ - int nCols, /**< Column number of matrix. */ - const char* name /**< Matlab name of matrix/vector to be stored. */ - ); - - -/** Returns the current system time. - * \return current system time */ -real_t qpOASES_getCPUtime( ); - - -/** Returns the N-norm of a vector. - * \return >= 0.0: successful */ -real_t qpOASES_getNorm( const real_t* const v, /**< Vector. */ - int n, /**< Vector's dimension. */ - int type /**< Norm type, 1: one-norm, 2: Euclidean norm. */ - ); - -/** Tests whether two real-valued arguments are (numerically) equal. - * \return BT_TRUE: arguments differ not more than TOL \n - BT_FALSE: arguments differ more than TOL */ -static inline BooleanType qpOASES_isEqual( real_t x, /**< First real number. */ - real_t y, /**< Second real number. */ - real_t TOL /**< Tolerance for comparison. */ - ); - - -/** Tests whether a real-valued argument is (numerically) zero. - * \return BT_TRUE: argument differs from 0.0 not more than TOL \n - BT_FALSE: argument differs from 0.0 more than TOL */ -static inline BooleanType qpOASES_isZero( real_t x, /**< Real number. */ - real_t TOL /**< Tolerance for comparison. */ - ); - - -/** Returns sign of a real-valued argument. - * \return 1.0: argument is non-negative \n - -1.0: argument is negative */ -static inline real_t qpOASES_getSign( real_t arg /**< real-valued argument whose sign is to be determined. */ - ); - - -/** Returns maximum of two integers. - * \return Maximum of two integers */ -static inline int qpOASES_getMaxI( int x, /**< First integer. */ - int y /**< Second integer. */ - ); - - -/** Returns minimum of two integers. - * \return Minimum of two integers */ -static inline int qpOASES_getMinI( int x, /**< First integer. */ - int y /**< Second integer. */ - ); - - -/** Returns maximum of two reals. - * \return Maximum of two reals */ -static inline real_t qpOASES_getMax( real_t x, /**< First real number. */ - real_t y /**< Second real number. */ - ); - - -/** Returns minimum of two reals. - * \return Minimum of two reals */ -static inline real_t qpOASES_getMin( real_t x, /**< First real number. */ - real_t y /**< Second real number. */ - ); - - -/** Returns the absolute value of a real_t-valued argument. - * \return Absolute value of a real_t-valued argument */ -static inline real_t qpOASES_getAbs( real_t x /**< real_t-valued argument. */ - ); - -/** Returns the square-root of a real number. - * \return Square-root of a real number */ -static inline real_t qpOASES_getSqrt( real_t x /**< Non-negative real number. */ - ); - - -/** Computes the maximum violation of the KKT optimality conditions - * of given iterate for given QP data. */ -returnValue qpOASES_getKktViolation( int nV, /**< Number of variables. */ - int nC, /**< Number of constraints. */ - const real_t* const H, /**< Hessian matrix (may be NULL if Hessian is zero or identity matrix). */ - const real_t* const g, /**< Gradient vector. */ - const real_t* const A, /**< Constraint matrix. */ - const real_t* const lb, /**< Lower bound vector (on variables). */ - const real_t* const ub, /**< Upper bound vector (on variables). */ - const real_t* const lbA, /**< Lower constraints' bound vector. */ - const real_t* const ubA, /**< Upper constraints' bound vector. */ - const real_t* const x, /**< Primal trial vector. */ - const real_t* const y, /**< Dual trial vector. */ - real_t* const _stat, /**< Output: maximum value of stationarity condition residual. */ - real_t* const feas, /**< Output: maximum value of primal feasibility violation. */ - real_t* const cmpl /**< Output: maximum value of complementarity residual. */ - ); - -/** Computes the maximum violation of the KKT optimality conditions - * of given iterate for given QP data. */ -returnValue qpOASES_getKktViolationSB( int nV, /**< Number of variables. */ - const real_t* const H, /**< Hessian matrix (may be NULL if Hessian is zero or identity matrix). */ - const real_t* const g, /**< Gradient vector. */ - const real_t* const lb, /**< Lower bound vector (on variables). */ - const real_t* const ub, /**< Upper bound vector (on variables). */ - const real_t* const x, /**< Primal trial vector. */ - const real_t* const y, /**< Dual trial vector. */ - real_t* const _stat, /**< Output: maximum value of stationarity condition residual. */ - real_t* const feas, /**< Output: maximum value of primal feasibility violation. */ - real_t* const cmpl /**< Output: maximum value of complementarity residual. */ - ); - - -/** Writes a value of BooleanType into a string. - * \return SUCCESSFUL_RETURN */ -returnValue qpOASES_convertBooleanTypeToString( BooleanType value, /**< Value to be written. */ - char* const string /**< Input: String of sufficient size, \n - Output: String containing value. */ - ); - -/** Writes a value of SubjectToStatus into a string. - * \return SUCCESSFUL_RETURN */ -returnValue qpOASES_convertSubjectToStatusToString( SubjectToStatus value, /**< Value to be written. */ - char* const string /**< Input: String of sufficient size, \n - Output: String containing value. */ - ); - -/** Writes a value of PrintLevel into a string. - * \return SUCCESSFUL_RETURN */ -returnValue qpOASES_convertPrintLevelToString( PrintLevel value, /**< Value to be written. */ - char* const string /**< Input: String of sufficient size, \n - Output: String containing value. */ - ); - - -/** Converts a returnValue from an QProblem(B) object into a more - * simple status flag. - * - * \return 0: QP problem solved - * 1: QP could not be solved within given number of iterations - * -1: QP could not be solved due to an internal error - * -2: QP is infeasible (and thus could not be solved) - * -3: QP is unbounded (and thus could not be solved) - */ -int qpOASES_getSimpleStatus( returnValue returnvalue, /**< ReturnValue to be analysed. */ - BooleanType doPrintStatus /**< Flag indicating whether simple status shall be printed to screen. */ - ); - -/** Normalises QP constraints. - * \return SUCCESSFUL_RETURN \n - * RET_INVALID_ARGUMENTS */ -returnValue qpOASES_normaliseConstraints( int nV, /**< Number of variables. */ - int nC, /**< Number of constraints. */ - real_t* A, /**< Input: Constraint matrix, \n - Output: Normalised constraint matrix. */ - real_t* lbA, /**< Input: Constraints' lower bound vector, \n - Output: Normalised constraints' lower bound vector. */ - real_t* ubA, /**< Input: Constraints' upper bound vector, \n - Output: Normalised constraints' upper bound vector. */ - int type /**< Norm type, 1: one-norm, 2: Euclidean norm. */ - ); - - -#ifdef __DEBUG__ -/** Writes matrix with given dimension into specified file. */ -void gdb_printmat( const char *fname, /**< File name. */ - real_t *M, /**< Matrix to be written. */ - int n, /**< Number of rows. */ - int m, /**< Number of columns. */ - int ldim /**< Leading dimension. */ - ); -#endif /* __DEBUG__ */ - - -#if defined(__DSPACE__) || defined(__XPCTARGET__) -void __cxa_pure_virtual( void ); -#endif /* __DSPACE__ || __XPCTARGET__*/ - - - -/* - * i s E q u a l - */ -static inline BooleanType qpOASES_isEqual( real_t x, - real_t y, - real_t TOL - ) -{ - if ( qpOASES_getAbs(x-y) <= TOL ) - return BT_TRUE; - else - return BT_FALSE; -} - - -/* - * i s Z e r o - */ -static inline BooleanType qpOASES_isZero( real_t x, - real_t TOL - ) -{ - if ( qpOASES_getAbs(x) <= TOL ) - return BT_TRUE; - else - return BT_FALSE; -} - - -/* - * g e t S i g n - */ -static inline real_t qpOASES_getSign( real_t arg - ) -{ - if ( arg >= 0.0 ) - return 1.0; - else - return -1.0; -} - - - -/* - * g e t M a x - */ -static inline int qpOASES_getMaxI( int x, - int y - ) -{ - return (yx) ? x : y; -} - - -/* - * g e t M a x - */ -static inline real_t qpOASES_getMax( real_t x, - real_t y - ) -{ - #ifdef __NO_FMATH__ - return (yx) ? x : y; - #else - return (y>x) ? x : y; - /*return fmin(x,y); seems to be slower */ - #endif -} - - -/* - * g e t A b s - */ -static inline real_t qpOASES_getAbs( real_t x - ) -{ - #ifdef __NO_FMATH__ - return (x>=0.0) ? x : -x; - #else - return fabs(x); - #endif -} - -/* - * g e t S q r t - */ -static inline real_t qpOASES_getSqrt( real_t x - ) -{ - #ifdef __NO_FMATH__ - return sqrt(x); /* put your custom sqrt-replacement here */ - #else - return sqrt(x); - #endif -} - - -END_NAMESPACE_QPOASES - - -#endif /* QPOASES_UTILS_H */ - - -/* - * end of file - */ diff --git a/third_party/acados/include/qpOASES_e/extras/OQPinterface.h b/third_party/acados/include/qpOASES_e/extras/OQPinterface.h deleted file mode 100644 index da59ea9db6..0000000000 --- a/third_party/acados/include/qpOASES_e/extras/OQPinterface.h +++ /dev/null @@ -1,227 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/extras/OQPinterface.h - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - * - * Declaration of an interface comprising several utility functions - * for solving test problems from the Online QP Benchmark Collection - * (This collection is no longer maintained, see - * http://www.qpOASES.org/onlineQP for a backup). - */ - - -#ifndef QPOASES_OQPINTERFACE_H -#define QPOASES_OQPINTERFACE_H - - -#include -#include - -#include -#include - - -BEGIN_NAMESPACE_QPOASES - -typedef struct { - QProblem *qp; - - DenseMatrix *H; - DenseMatrix *A; - - real_t *x; - real_t *y; -} OQPbenchmark_ws; - -int OQPbenchmark_ws_calculateMemorySize( unsigned int nV, unsigned int nC ); - -char *OQPbenchmark_ws_assignMemory( unsigned int nV, unsigned int nC, OQPbenchmark_ws **mem, void *raw_memory ); - -OQPbenchmark_ws *OQPbenchmark_ws_createMemory( unsigned int nV, unsigned int nC ); - -typedef struct { - QProblemB *qp; - - DenseMatrix *H; - - real_t *x; - real_t *y; -} OQPbenchmarkB_ws; - -int OQPbenchmarkB_ws_calculateMemorySize( unsigned int nV ); - -char *OQPbenchmarkB_ws_assignMemory( unsigned int nV, OQPbenchmarkB_ws **mem, void *raw_memory ); - -OQPbenchmarkB_ws *OQPbenchmarkB_ws_createMemory( unsigned int nV ); - -typedef struct { - OQPbenchmark_ws *qp_ws; - OQPbenchmarkB_ws *qpB_ws; - - real_t *H; - real_t *g; - real_t *A; - real_t *lb; - real_t *ub; - real_t *lbA; - real_t *ubA; -} OQPinterface_ws; - -int OQPinterface_ws_calculateMemorySize( unsigned int nV, unsigned int nC, unsigned int nQP ); - -char *OQPinterface_ws_assignMemory( unsigned int nV, unsigned int nC, unsigned int nQP, OQPinterface_ws **mem, void *raw_memory ); - -OQPinterface_ws *OQPinterface_ws_createMemory( unsigned int nV, unsigned int nC, unsigned int nQP ); - -/** Reads dimensions of an Online QP Benchmark problem from file. - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_READ_FILE \n - RET_FILEDATA_INCONSISTENT */ -returnValue readOQPdimensions( const char* path, /**< Full path of the data files (without trailing slash!). */ - int* nQP, /**< Output: Number of QPs. */ - int* nV, /**< Output: Number of variables. */ - int* nC, /**< Output: Number of constraints. */ - int* nEC /**< Output: Number of equality constraints. */ - ); - -/** Reads data of an Online QP Benchmark problem from file. - * This function allocates the required memory for all data; after successfully calling it, - * you have to free this memory yourself! - * \return SUCCESSFUL_RETURN \n - RET_INVALID_ARGUMENTS \n - RET_UNABLE_TO_READ_FILE \n - RET_FILEDATA_INCONSISTENT */ -returnValue readOQPdata( const char* path, /**< Full path of the data files (without trailing slash!). */ - int* nQP, /**< Output: Number of QPs. */ - int* nV, /**< Output: Number of variables. */ - int* nC, /**< Output: Number of constraints. */ - int* nEC, /**< Output: Number of equality constraints. */ - real_t* H, /**< Output: Hessian matrix. */ - real_t* g, /**< Output: Sequence of gradient vectors. */ - real_t* A, /**< Output: Constraint matrix. */ - real_t* lb, /**< Output: Sequence of lower bound vectors (on variables). */ - real_t* ub, /**< Output: Sequence of upper bound vectors (on variables). */ - real_t* lbA, /**< Output: Sequence of lower constraints' bound vectors. */ - real_t* ubA, /**< Output: Sequence of upper constraints' bound vectors. */ - real_t* xOpt, /**< Output: Sequence of primal solution vectors - * (not read if a null pointer is passed). */ - real_t* yOpt, /**< Output: Sequence of dual solution vectors - * (not read if a null pointer is passed). */ - real_t* objOpt /**< Output: Sequence of optimal objective function values - * (not read if a null pointer is passed). */ - ); - - -/** Solves an Online QP Benchmark problem as specified by the arguments. - * The maximum deviations from the given optimal solution as well as the - * maximum CPU time to solve each QP are determined. - * \return SUCCESSFUL_RETURN \n - RET_BENCHMARK_ABORTED */ -returnValue solveOQPbenchmark( int nQP, /**< Number of QPs. */ - int nV, /**< Number of variables. */ - int nC, /**< Number of constraints. */ - int nEC, /**< Number of equality constraints. */ - real_t* _H, /**< Hessian matrix. */ - const real_t* const g, /**< Sequence of gradient vectors. */ - real_t* _A, /**< Constraint matrix. */ - const real_t* const lb, /**< Sequence of lower bound vectors (on variables). */ - const real_t* const ub, /**< Sequence of upper bound vectors (on variables). */ - const real_t* const lbA, /**< Sequence of lower constraints' bound vectors. */ - const real_t* const ubA, /**< Sequence of upper constraints' bound vectors. */ - BooleanType isSparse, /**< Shall convert matrices to sparse format before solution? */ - BooleanType useHotstarts, /**< Shall QP solution be hotstarted? */ - const Options* options, /**< QP solver options to be used while solving benchmark problems. */ - int maxAllowedNWSR, /**< Maximum number of working set recalculations to be performed. */ - real_t* maxNWSR, /**< Output: Maximum number of performed working set recalculations. */ - real_t* avgNWSR, /**< Output: Average number of performed working set recalculations. */ - real_t* maxCPUtime, /**< Output: Maximum CPU time required for solving each QP. */ - real_t* avgCPUtime, /**< Output: Average CPU time required for solving each QP. */ - real_t* maxStationarity, /**< Output: Maximum residual of stationarity condition. */ - real_t* maxFeasibility, /**< Output: Maximum residual of primal feasibility condition. */ - real_t* maxComplementarity, /**< Output: Maximum residual of complementarity condition. */ - OQPbenchmark_ws *work /**< Workspace. */ - ); - -/** Solves an Online QP Benchmark problem (without constraints) as specified - * by the arguments. The maximum deviations from the given optimal solution - * as well as the maximum CPU time to solve each QP are determined. - * \return SUCCESSFUL_RETURN \n - RET_BENCHMARK_ABORTED */ -returnValue solveOQPbenchmarkB( int nQP, /**< Number of QPs. */ - int nV, /**< Number of variables. */ - real_t* _H, /**< Hessian matrix. */ - const real_t* const g, /**< Sequence of gradient vectors. */ - const real_t* const lb, /**< Sequence of lower bound vectors (on variables). */ - const real_t* const ub, /**< Sequence of upper bound vectors (on variables). */ - BooleanType isSparse, /**< Shall convert matrices to sparse format before solution? */ - BooleanType useHotstarts, /**< Shall QP solution be hotstarted? */ - const Options* options, /**< QP solver options to be used while solving benchmark problems. */ - int maxAllowedNWSR, /**< Maximum number of working set recalculations to be performed. */ - real_t* maxNWSR, /**< Output: Maximum number of performed working set recalculations. */ - real_t* avgNWSR, /**< Output: Average number of performed working set recalculations. */ - real_t* maxCPUtime, /**< Output: Maximum CPU time required for solving each QP. */ - real_t* avgCPUtime, /**< Output: Average CPU time required for solving each QP. */ - real_t* maxStationarity, /**< Output: Maximum residual of stationarity condition. */ - real_t* maxFeasibility, /**< Output: Maximum residual of primal feasibility condition. */ - real_t* maxComplementarity, /**< Output: Maximum residual of complementarity condition. */ - OQPbenchmarkB_ws *work /**< Workspace. */ - ); - - -/** Runs an Online QP Benchmark problem and determines the maximum - * violation of the KKT optimality conditions as well as the - * maximum and average number of iterations and CPU time to solve - * each QP. - * - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_READ_BENCHMARK \n - RET_BENCHMARK_ABORTED */ -returnValue runOQPbenchmark( const char* path, /**< Full path of the benchmark files (without trailing slash!). */ - BooleanType isSparse, /**< Shall convert matrices to sparse format before solution? */ - BooleanType useHotstarts, /**< Shall QP solution be hotstarted? */ - const Options* options, /**< QP solver options to be used while solving benchmark problems. */ - int maxAllowedNWSR, /**< Maximum number of working set recalculations to be performed. */ - real_t* maxNWSR, /**< Output: Maximum number of performed working set recalculations. */ - real_t* avgNWSR, /**< Output: Average number of performed working set recalculations. */ - real_t* maxCPUtime, /**< Output: Maximum CPU time required for solving each QP. */ - real_t* avgCPUtime, /**< Output: Average CPU time required for solving each QP. */ - real_t* maxStationarity, /**< Output: Maximum residual of stationarity condition. */ - real_t* maxFeasibility, /**< Output: Maximum residual of primal feasibility condition. */ - real_t* maxComplementarity, /**< Output: Maximum residual of complementarity condition. */ - OQPinterface_ws* work /**< Workspace. */ - ); - -END_NAMESPACE_QPOASES - - -#endif /* QPOASES_OQPINTERFACE_H */ - - -/* - * end of file - */ diff --git a/third_party/acados/larch64/lib/libacados.so b/third_party/acados/larch64/lib/libacados.so deleted file mode 100644 index a081e31ab1..0000000000 --- a/third_party/acados/larch64/lib/libacados.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:091ed10ea2b52866b826ef6867b3413d6fd61af66fcedf3d932c9adf3fb329de -size 512912 diff --git a/third_party/acados/larch64/lib/libblasfeo.so b/third_party/acados/larch64/lib/libblasfeo.so deleted file mode 100644 index e2191897a1..0000000000 --- a/third_party/acados/larch64/lib/libblasfeo.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:d40b25de85318c8349c9894a3cbeaa713efae4158d8cc2c5c77af9f1bfbbb28e -size 1150320 diff --git a/third_party/acados/larch64/lib/libhpipm.so b/third_party/acados/larch64/lib/libhpipm.so deleted file mode 100644 index 002eda375a..0000000000 --- a/third_party/acados/larch64/lib/libhpipm.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:91b9276e74c7d7750288d76087d586ed27932939bc7bca2ad1494b6558fc43e3 -size 1367352 diff --git a/third_party/acados/larch64/lib/libqpOASES_e.so b/third_party/acados/larch64/lib/libqpOASES_e.so deleted file mode 120000 index 14048625a1..0000000000 --- a/third_party/acados/larch64/lib/libqpOASES_e.so +++ /dev/null @@ -1 +0,0 @@ -libqpOASES_e.so.3.1 \ No newline at end of file diff --git a/third_party/acados/larch64/lib/libqpOASES_e.so.3.1 b/third_party/acados/larch64/lib/libqpOASES_e.so.3.1 deleted file mode 100644 index d64e40ec60..0000000000 --- a/third_party/acados/larch64/lib/libqpOASES_e.so.3.1 +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:c0a84042e5315af18e6e33b9b9c5e96573248e41ff165657eb9d83da4da2889f -size 223152 diff --git a/third_party/acados/larch64/t_renderer b/third_party/acados/larch64/t_renderer deleted file mode 100755 index f9e7d16601..0000000000 --- a/third_party/acados/larch64/t_renderer +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:4660fe00e03e29d90459ac2fd46a6e10982577d0ba558b9f05e5712df66814b4 -size 17915048 diff --git a/third_party/acados/x86_64/lib/libacados.so b/third_party/acados/x86_64/lib/libacados.so deleted file mode 100644 index 50d647a862..0000000000 --- a/third_party/acados/x86_64/lib/libacados.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:05a1ba3cf37fa929cdd56f892608b2f89c35a05ef1b07fedb86b2f0d76607263 -size 540488 diff --git a/third_party/acados/x86_64/lib/libblasfeo.so b/third_party/acados/x86_64/lib/libblasfeo.so deleted file mode 100644 index a98f45abd2..0000000000 --- a/third_party/acados/x86_64/lib/libblasfeo.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:c0bf22898d9c59b672d3d0961f5f4c804b9957478125d99eb297de3091bedd15 -size 2416112 diff --git a/third_party/acados/x86_64/lib/libhpipm.so b/third_party/acados/x86_64/lib/libhpipm.so deleted file mode 100644 index f40cb487cd..0000000000 --- a/third_party/acados/x86_64/lib/libhpipm.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:5b6875fb47940764d4ebb916c2373cb0e04929229feb654b290676c28d48fa9d -size 1531024 diff --git a/third_party/acados/x86_64/lib/libqpOASES_e.so b/third_party/acados/x86_64/lib/libqpOASES_e.so deleted file mode 120000 index 14048625a1..0000000000 --- a/third_party/acados/x86_64/lib/libqpOASES_e.so +++ /dev/null @@ -1 +0,0 @@ -libqpOASES_e.so.3.1 \ No newline at end of file diff --git a/third_party/acados/x86_64/lib/libqpOASES_e.so.3.1 b/third_party/acados/x86_64/lib/libqpOASES_e.so.3.1 deleted file mode 100644 index 81afd059f7..0000000000 --- a/third_party/acados/x86_64/lib/libqpOASES_e.so.3.1 +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:04be908c3f707e5c968022b9cdd79ab75ae7af46e7fa019ceee98f854ddd3f64 -size 262464 diff --git a/third_party/acados/x86_64/t_renderer b/third_party/acados/x86_64/t_renderer deleted file mode 100755 index d41f6c3725..0000000000 --- a/third_party/acados/x86_64/t_renderer +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:a53ae46650c4df5b0ddb87a658f59a0422e41743e8bc2d822da0aefd1d280791 -size 5088536 diff --git a/third_party/bootstrap/.gitignore b/third_party/bootstrap/.gitignore deleted file mode 100644 index ac06c0cf85..0000000000 --- a/third_party/bootstrap/.gitignore +++ /dev/null @@ -1 +0,0 @@ -/icons/ diff --git a/third_party/bootstrap/bootstrap-icons.svg b/third_party/bootstrap/bootstrap-icons.svg deleted file mode 100644 index 692a27ea55..0000000000 --- a/third_party/bootstrap/bootstrap-icons.svg +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:d7ecfaac355e51c9b95319fdf4681cf4c423109fd477e961af588b92607a76da -size 1087239 diff --git a/third_party/bootstrap/bootstrap-icons.ttf b/third_party/bootstrap/bootstrap-icons.ttf deleted file mode 100644 index 49c8ea699a..0000000000 --- a/third_party/bootstrap/bootstrap-icons.ttf +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:57e798d421bb56bb058ed9b0c83dd97fe1e411cde3a2bd6eb4a8705234f69027 -size 453096 diff --git a/third_party/bootstrap/pull.sh b/third_party/bootstrap/pull.sh deleted file mode 100755 index 5c4c955c04..0000000000 --- a/third_party/bootstrap/pull.sh +++ /dev/null @@ -1,24 +0,0 @@ -#!/bin/bash -set -e - -DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )" -cd $DIR - -if [ ! -d icons/ ]; then - git clone https://github.com/twbs/icons/ -fi - -cd icons -git fetch --all -git checkout d5aa187483a1b0b186f87adcfa8576350d970d98 -cp bootstrap-icons.svg ../ - -# Convert WOFF → TTF for imgui (imgui only reads TTF/OTF) -python3 -c " -from fontTools.ttLib import TTFont -import io -f = TTFont('font/fonts/bootstrap-icons.woff') -f.flavor = None -f.save('../bootstrap-icons.ttf') -print('bootstrap-icons.ttf written') -" diff --git a/third_party/build.sh b/third_party/build.sh deleted file mode 100755 index d3a9c6579c..0000000000 --- a/third_party/build.sh +++ /dev/null @@ -1,53 +0,0 @@ -#!/usr/bin/env bash -set -e - -DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" - -# Reproducible builds: pin timestamps to epoch -export SOURCE_DATE_EPOCH=0 -export ZERO_AR_DATE=1 - -pids=() -names=() -logs=() - -for script in "$DIR"/*/build.sh; do - [ -f "$script" ] || continue - name=$(basename "$(dirname "$script")") - log=$(mktemp) - names+=("$name") - logs+=("$log") - (cd "$(dirname "$script")" && bash "$(basename "$script")") >"$log" 2>&1 & - pids+=($!) -done - -failed=0 -for i in "${!pids[@]}"; do - echo "--- ${names[$i]} ---" - if wait "${pids[$i]}"; then - echo "OK" - else - echo "FAILED (exit $?)" - failed=1 - fi - cat "${logs[$i]}" - rm -f "${logs[$i]}" - echo -done - -[ $failed -ne 0 ] && exit $failed - -# Repack ar archives with deterministic headers (zero timestamps/uid/gid) -# Skip foreign-platform archives that ar can't read (e.g. Mach-O on Linux) -while IFS= read -r -d '' lib; do - tmpdir=$(mktemp -d) - lib=$(realpath "$lib") - if (cd "$tmpdir" && ar x "$lib" 2>/dev/null); then - (cd "$tmpdir" && ar Drcs repacked.a * && mv repacked.a "$lib") - fi - rm -rf "$tmpdir" -done < <(find "$DIR" -name '*.a' \ - \( -path '*/x86_64/*' -o -path '*/Darwin/*' -o -path '*/larch64/*' -o -path '*/aarch64/*' \) \ - -print0) - -echo -e "\033[32mAll third_party builds succeeded.\033[0m" diff --git a/third_party/catch2/include/catch2/catch.hpp b/third_party/catch2/include/catch2/catch.hpp deleted file mode 100644 index 6a31e5b0ca..0000000000 --- a/third_party/catch2/include/catch2/catch.hpp +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:27da57c7a06d09be8dd81fab7246b79e7892b6ae7e4e49ba8631f1d5a955e3fc -size 657276 diff --git a/third_party/catch2/include/catch2/catch_reporter_automake.hpp b/third_party/catch2/include/catch2/catch_reporter_automake.hpp deleted file mode 100644 index dbebe97516..0000000000 --- a/third_party/catch2/include/catch2/catch_reporter_automake.hpp +++ /dev/null @@ -1,62 +0,0 @@ -/* - * Created by Justin R. Wilson on 2/19/2017. - * Copyright 2017 Justin R. Wilson. All rights reserved. - * - * Distributed under the Boost Software License, Version 1.0. (See accompanying - * file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) - */ -#ifndef TWOBLUECUBES_CATCH_REPORTER_AUTOMAKE_HPP_INCLUDED -#define TWOBLUECUBES_CATCH_REPORTER_AUTOMAKE_HPP_INCLUDED - -// Don't #include any Catch headers here - we can assume they are already -// included before this header. -// This is not good practice in general but is necessary in this case so this -// file can be distributed as a single header that works with the main -// Catch single header. - -namespace Catch { - - struct AutomakeReporter : StreamingReporterBase { - AutomakeReporter( ReporterConfig const& _config ) - : StreamingReporterBase( _config ) - {} - - ~AutomakeReporter() override; - - static std::string getDescription() { - return "Reports test results in the format of Automake .trs files"; - } - - void assertionStarting( AssertionInfo const& ) override {} - - bool assertionEnded( AssertionStats const& /*_assertionStats*/ ) override { return true; } - - void testCaseEnded( TestCaseStats const& _testCaseStats ) override { - // Possible values to emit are PASS, XFAIL, SKIP, FAIL, XPASS and ERROR. - stream << ":test-result: "; - if (_testCaseStats.totals.assertions.allPassed()) { - stream << "PASS"; - } else if (_testCaseStats.totals.assertions.allOk()) { - stream << "XFAIL"; - } else { - stream << "FAIL"; - } - stream << ' ' << _testCaseStats.testInfo.name << '\n'; - StreamingReporterBase::testCaseEnded( _testCaseStats ); - } - - void skipTest( TestCaseInfo const& testInfo ) override { - stream << ":test-result: SKIP " << testInfo.name << '\n'; - } - - }; - -#ifdef CATCH_IMPL - AutomakeReporter::~AutomakeReporter() {} -#endif - - CATCH_REGISTER_REPORTER( "automake", AutomakeReporter) - -} // end namespace Catch - -#endif // TWOBLUECUBES_CATCH_REPORTER_AUTOMAKE_HPP_INCLUDED diff --git a/third_party/catch2/include/catch2/catch_reporter_sonarqube.hpp b/third_party/catch2/include/catch2/catch_reporter_sonarqube.hpp deleted file mode 100644 index bf7d9299a5..0000000000 --- a/third_party/catch2/include/catch2/catch_reporter_sonarqube.hpp +++ /dev/null @@ -1,181 +0,0 @@ -/* - * Created by Daniel Garcia on 2018-12-04. - * Copyright Social Point SL. All rights reserved. - * - * Distributed under the Boost Software License, Version 1.0. (See accompanying - * file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) - */ -#ifndef CATCH_REPORTER_SONARQUBE_HPP_INCLUDED -#define CATCH_REPORTER_SONARQUBE_HPP_INCLUDED - - -// Don't #include any Catch headers here - we can assume they are already -// included before this header. -// This is not good practice in general but is necessary in this case so this -// file can be distributed as a single header that works with the main -// Catch single header. - -#include - -namespace Catch { - - struct SonarQubeReporter : CumulativeReporterBase { - - SonarQubeReporter(ReporterConfig const& config) - : CumulativeReporterBase(config) - , xml(config.stream()) { - m_reporterPrefs.shouldRedirectStdOut = true; - m_reporterPrefs.shouldReportAllAssertions = true; - } - - ~SonarQubeReporter() override; - - static std::string getDescription() { - return "Reports test results in the Generic Test Data SonarQube XML format"; - } - - static std::set getSupportedVerbosities() { - return { Verbosity::Normal }; - } - - void noMatchingTestCases(std::string const& /*spec*/) override {} - - void testRunStarting(TestRunInfo const& testRunInfo) override { - CumulativeReporterBase::testRunStarting(testRunInfo); - xml.startElement("testExecutions"); - xml.writeAttribute("version", "1"); - } - - void testGroupEnded(TestGroupStats const& testGroupStats) override { - CumulativeReporterBase::testGroupEnded(testGroupStats); - writeGroup(*m_testGroups.back()); - } - - void testRunEndedCumulative() override { - xml.endElement(); - } - - void writeGroup(TestGroupNode const& groupNode) { - std::map testsPerFile; - for(auto const& child : groupNode.children) - testsPerFile[child->value.testInfo.lineInfo.file].push_back(child); - - for(auto const& kv : testsPerFile) - writeTestFile(kv.first.c_str(), kv.second); - } - - void writeTestFile(const char* filename, TestGroupNode::ChildNodes const& testCaseNodes) { - XmlWriter::ScopedElement e = xml.scopedElement("file"); - xml.writeAttribute("path", filename); - - for(auto const& child : testCaseNodes) - writeTestCase(*child); - } - - void writeTestCase(TestCaseNode const& testCaseNode) { - // All test cases have exactly one section - which represents the - // test case itself. That section may have 0-n nested sections - assert(testCaseNode.children.size() == 1); - SectionNode const& rootSection = *testCaseNode.children.front(); - writeSection("", rootSection, testCaseNode.value.testInfo.okToFail()); - } - - void writeSection(std::string const& rootName, SectionNode const& sectionNode, bool okToFail) { - std::string name = trim(sectionNode.stats.sectionInfo.name); - if(!rootName.empty()) - name = rootName + '/' + name; - - if(!sectionNode.assertions.empty() || !sectionNode.stdOut.empty() || !sectionNode.stdErr.empty()) { - XmlWriter::ScopedElement e = xml.scopedElement("testCase"); - xml.writeAttribute("name", name); - xml.writeAttribute("duration", static_cast(sectionNode.stats.durationInSeconds * 1000)); - - writeAssertions(sectionNode, okToFail); - } - - for(auto const& childNode : sectionNode.childSections) - writeSection(name, *childNode, okToFail); - } - - void writeAssertions(SectionNode const& sectionNode, bool okToFail) { - for(auto const& assertion : sectionNode.assertions) - writeAssertion( assertion, okToFail); - } - - void writeAssertion(AssertionStats const& stats, bool okToFail) { - AssertionResult const& result = stats.assertionResult; - if(!result.isOk()) { - std::string elementName; - if(okToFail) { - elementName = "skipped"; - } - else { - switch(result.getResultType()) { - case ResultWas::ThrewException: - case ResultWas::FatalErrorCondition: - elementName = "error"; - break; - case ResultWas::ExplicitFailure: - elementName = "failure"; - break; - case ResultWas::ExpressionFailed: - elementName = "failure"; - break; - case ResultWas::DidntThrowException: - elementName = "failure"; - break; - - // We should never see these here: - case ResultWas::Info: - case ResultWas::Warning: - case ResultWas::Ok: - case ResultWas::Unknown: - case ResultWas::FailureBit: - case ResultWas::Exception: - elementName = "internalError"; - break; - } - } - - XmlWriter::ScopedElement e = xml.scopedElement(elementName); - - ReusableStringStream messageRss; - messageRss << result.getTestMacroName() << "(" << result.getExpression() << ")"; - xml.writeAttribute("message", messageRss.str()); - - ReusableStringStream textRss; - if (stats.totals.assertions.total() > 0) { - textRss << "FAILED:\n"; - if (result.hasExpression()) { - textRss << "\t" << result.getExpressionInMacro() << "\n"; - } - if (result.hasExpandedExpression()) { - textRss << "with expansion:\n\t" << result.getExpandedExpression() << "\n"; - } - } - - if(!result.getMessage().empty()) - textRss << result.getMessage() << "\n"; - - for(auto const& msg : stats.infoMessages) - if(msg.type == ResultWas::Info) - textRss << msg.message << "\n"; - - textRss << "at " << result.getSourceInfo(); - xml.writeText(textRss.str(), XmlFormatting::Newline); - } - } - - private: - XmlWriter xml; - }; - -#ifdef CATCH_IMPL - SonarQubeReporter::~SonarQubeReporter() {} -#endif - - CATCH_REGISTER_REPORTER( "sonarqube", SonarQubeReporter ) - -} // end namespace Catch - -#endif // CATCH_REPORTER_SONARQUBE_HPP_INCLUDED \ No newline at end of file diff --git a/third_party/catch2/include/catch2/catch_reporter_tap.hpp b/third_party/catch2/include/catch2/catch_reporter_tap.hpp deleted file mode 100644 index 5ac8524ce7..0000000000 --- a/third_party/catch2/include/catch2/catch_reporter_tap.hpp +++ /dev/null @@ -1,254 +0,0 @@ -/* - * Created by Colton Wolkins on 2015-08-15. - * Copyright 2015 Martin Moene. All rights reserved. - * - * Distributed under the Boost Software License, Version 1.0. (See accompanying - * file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) - */ -#ifndef TWOBLUECUBES_CATCH_REPORTER_TAP_HPP_INCLUDED -#define TWOBLUECUBES_CATCH_REPORTER_TAP_HPP_INCLUDED - - -// Don't #include any Catch headers here - we can assume they are already -// included before this header. -// This is not good practice in general but is necessary in this case so this -// file can be distributed as a single header that works with the main -// Catch single header. - -#include - -namespace Catch { - - struct TAPReporter : StreamingReporterBase { - - using StreamingReporterBase::StreamingReporterBase; - - TAPReporter( ReporterConfig const& config ): - StreamingReporterBase( config ) { - m_reporterPrefs.shouldReportAllAssertions = true; - } - - ~TAPReporter() override; - - static std::string getDescription() { - return "Reports test results in TAP format, suitable for test harnesses"; - } - - void noMatchingTestCases( std::string const& spec ) override { - stream << "# No test cases matched '" << spec << "'" << std::endl; - } - - void assertionStarting( AssertionInfo const& ) override {} - - bool assertionEnded( AssertionStats const& _assertionStats ) override { - ++counter; - - stream << "# " << currentTestCaseInfo->name << std::endl; - AssertionPrinter printer( stream, _assertionStats, counter ); - printer.print(); - - stream << std::endl; - return true; - } - - void testRunEnded( TestRunStats const& _testRunStats ) override { - printTotals( _testRunStats.totals ); - stream << "\n" << std::endl; - StreamingReporterBase::testRunEnded( _testRunStats ); - } - - private: - std::size_t counter = 0; - class AssertionPrinter { - public: - AssertionPrinter& operator= ( AssertionPrinter const& ) = delete; - AssertionPrinter( AssertionPrinter const& ) = delete; - AssertionPrinter( std::ostream& _stream, AssertionStats const& _stats, std::size_t _counter ) - : stream( _stream ) - , result( _stats.assertionResult ) - , messages( _stats.infoMessages ) - , itMessage( _stats.infoMessages.begin() ) - , printInfoMessages( true ) - , counter(_counter) - {} - - void print() { - itMessage = messages.begin(); - - switch( result.getResultType() ) { - case ResultWas::Ok: - printResultType( passedString() ); - printOriginalExpression(); - printReconstructedExpression(); - if ( ! result.hasExpression() ) - printRemainingMessages( Colour::None ); - else - printRemainingMessages(); - break; - case ResultWas::ExpressionFailed: - if (result.isOk()) { - printResultType(passedString()); - } else { - printResultType(failedString()); - } - printOriginalExpression(); - printReconstructedExpression(); - if (result.isOk()) { - printIssue(" # TODO"); - } - printRemainingMessages(); - break; - case ResultWas::ThrewException: - printResultType( failedString() ); - printIssue( "unexpected exception with message:" ); - printMessage(); - printExpressionWas(); - printRemainingMessages(); - break; - case ResultWas::FatalErrorCondition: - printResultType( failedString() ); - printIssue( "fatal error condition with message:" ); - printMessage(); - printExpressionWas(); - printRemainingMessages(); - break; - case ResultWas::DidntThrowException: - printResultType( failedString() ); - printIssue( "expected exception, got none" ); - printExpressionWas(); - printRemainingMessages(); - break; - case ResultWas::Info: - printResultType( "info" ); - printMessage(); - printRemainingMessages(); - break; - case ResultWas::Warning: - printResultType( "warning" ); - printMessage(); - printRemainingMessages(); - break; - case ResultWas::ExplicitFailure: - printResultType( failedString() ); - printIssue( "explicitly" ); - printRemainingMessages( Colour::None ); - break; - // These cases are here to prevent compiler warnings - case ResultWas::Unknown: - case ResultWas::FailureBit: - case ResultWas::Exception: - printResultType( "** internal error **" ); - break; - } - } - - private: - static Colour::Code dimColour() { return Colour::FileName; } - - static const char* failedString() { return "not ok"; } - static const char* passedString() { return "ok"; } - - void printSourceInfo() const { - Colour colourGuard( dimColour() ); - stream << result.getSourceInfo() << ":"; - } - - void printResultType( std::string const& passOrFail ) const { - if( !passOrFail.empty() ) { - stream << passOrFail << ' ' << counter << " -"; - } - } - - void printIssue( std::string const& issue ) const { - stream << " " << issue; - } - - void printExpressionWas() { - if( result.hasExpression() ) { - stream << ";"; - { - Colour colour( dimColour() ); - stream << " expression was:"; - } - printOriginalExpression(); - } - } - - void printOriginalExpression() const { - if( result.hasExpression() ) { - stream << " " << result.getExpression(); - } - } - - void printReconstructedExpression() const { - if( result.hasExpandedExpression() ) { - { - Colour colour( dimColour() ); - stream << " for: "; - } - std::string expr = result.getExpandedExpression(); - std::replace( expr.begin(), expr.end(), '\n', ' '); - stream << expr; - } - } - - void printMessage() { - if ( itMessage != messages.end() ) { - stream << " '" << itMessage->message << "'"; - ++itMessage; - } - } - - void printRemainingMessages( Colour::Code colour = dimColour() ) { - if (itMessage == messages.end()) { - return; - } - - const auto itEnd = messages.cend(); - const auto N = static_cast( std::distance( itMessage, itEnd ) ); - - { - Colour colourGuard( colour ); - stream << " with " << pluralise( N, "message" ) << ":"; - } - - while( itMessage != itEnd ) { - // If this assertion is a warning ignore any INFO messages - if( printInfoMessages || itMessage->type != ResultWas::Info ) { - stream << " '" << itMessage->message << "'"; - if ( ++itMessage != itEnd ) { - Colour colourGuard( dimColour() ); - stream << " and"; - } - continue; - } - ++itMessage; - } - } - - private: - std::ostream& stream; - AssertionResult const& result; - std::vector messages; - std::vector::const_iterator itMessage; - bool printInfoMessages; - std::size_t counter; - }; - - void printTotals( const Totals& totals ) const { - stream << "1.." << totals.assertions.total(); - if( totals.testCases.total() == 0 ) { - stream << " # Skipped: No tests ran."; - } - } - }; - -#ifdef CATCH_IMPL - TAPReporter::~TAPReporter() {} -#endif - - CATCH_REGISTER_REPORTER( "tap", TAPReporter ) - -} // end namespace Catch - -#endif // TWOBLUECUBES_CATCH_REPORTER_TAP_HPP_INCLUDED diff --git a/third_party/catch2/include/catch2/catch_reporter_teamcity.hpp b/third_party/catch2/include/catch2/catch_reporter_teamcity.hpp deleted file mode 100644 index 47b7e4aac3..0000000000 --- a/third_party/catch2/include/catch2/catch_reporter_teamcity.hpp +++ /dev/null @@ -1,219 +0,0 @@ -/* - * Created by Phil Nash on 19th December 2014 - * Copyright 2014 Two Blue Cubes Ltd. All rights reserved. - * - * Distributed under the Boost Software License, Version 1.0. (See accompanying - * file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) - */ -#ifndef TWOBLUECUBES_CATCH_REPORTER_TEAMCITY_HPP_INCLUDED -#define TWOBLUECUBES_CATCH_REPORTER_TEAMCITY_HPP_INCLUDED - -// Don't #include any Catch headers here - we can assume they are already -// included before this header. -// This is not good practice in general but is necessary in this case so this -// file can be distributed as a single header that works with the main -// Catch single header. - -#include - -#ifdef __clang__ -# pragma clang diagnostic push -# pragma clang diagnostic ignored "-Wpadded" -#endif - -namespace Catch { - - struct TeamCityReporter : StreamingReporterBase { - TeamCityReporter( ReporterConfig const& _config ) - : StreamingReporterBase( _config ) - { - m_reporterPrefs.shouldRedirectStdOut = true; - } - - static std::string escape( std::string const& str ) { - std::string escaped = str; - replaceInPlace( escaped, "|", "||" ); - replaceInPlace( escaped, "'", "|'" ); - replaceInPlace( escaped, "\n", "|n" ); - replaceInPlace( escaped, "\r", "|r" ); - replaceInPlace( escaped, "[", "|[" ); - replaceInPlace( escaped, "]", "|]" ); - return escaped; - } - ~TeamCityReporter() override; - - static std::string getDescription() { - return "Reports test results as TeamCity service messages"; - } - - void skipTest( TestCaseInfo const& /* testInfo */ ) override { - } - - void noMatchingTestCases( std::string const& /* spec */ ) override {} - - void testGroupStarting( GroupInfo const& groupInfo ) override { - StreamingReporterBase::testGroupStarting( groupInfo ); - stream << "##teamcity[testSuiteStarted name='" - << escape( groupInfo.name ) << "']\n"; - } - void testGroupEnded( TestGroupStats const& testGroupStats ) override { - StreamingReporterBase::testGroupEnded( testGroupStats ); - stream << "##teamcity[testSuiteFinished name='" - << escape( testGroupStats.groupInfo.name ) << "']\n"; - } - - - void assertionStarting( AssertionInfo const& ) override {} - - bool assertionEnded( AssertionStats const& assertionStats ) override { - AssertionResult const& result = assertionStats.assertionResult; - if( !result.isOk() ) { - - ReusableStringStream msg; - if( !m_headerPrintedForThisSection ) - printSectionHeader( msg.get() ); - m_headerPrintedForThisSection = true; - - msg << result.getSourceInfo() << "\n"; - - switch( result.getResultType() ) { - case ResultWas::ExpressionFailed: - msg << "expression failed"; - break; - case ResultWas::ThrewException: - msg << "unexpected exception"; - break; - case ResultWas::FatalErrorCondition: - msg << "fatal error condition"; - break; - case ResultWas::DidntThrowException: - msg << "no exception was thrown where one was expected"; - break; - case ResultWas::ExplicitFailure: - msg << "explicit failure"; - break; - - // We shouldn't get here because of the isOk() test - case ResultWas::Ok: - case ResultWas::Info: - case ResultWas::Warning: - CATCH_ERROR( "Internal error in TeamCity reporter" ); - // These cases are here to prevent compiler warnings - case ResultWas::Unknown: - case ResultWas::FailureBit: - case ResultWas::Exception: - CATCH_ERROR( "Not implemented" ); - } - if( assertionStats.infoMessages.size() == 1 ) - msg << " with message:"; - if( assertionStats.infoMessages.size() > 1 ) - msg << " with messages:"; - for( auto const& messageInfo : assertionStats.infoMessages ) - msg << "\n \"" << messageInfo.message << "\""; - - - if( result.hasExpression() ) { - msg << - "\n " << result.getExpressionInMacro() << "\n" - "with expansion:\n" << - " " << result.getExpandedExpression() << "\n"; - } - - if( currentTestCaseInfo->okToFail() ) { - msg << "- failure ignore as test marked as 'ok to fail'\n"; - stream << "##teamcity[testIgnored" - << " name='" << escape( currentTestCaseInfo->name )<< "'" - << " message='" << escape( msg.str() ) << "'" - << "]\n"; - } - else { - stream << "##teamcity[testFailed" - << " name='" << escape( currentTestCaseInfo->name )<< "'" - << " message='" << escape( msg.str() ) << "'" - << "]\n"; - } - } - stream.flush(); - return true; - } - - void sectionStarting( SectionInfo const& sectionInfo ) override { - m_headerPrintedForThisSection = false; - StreamingReporterBase::sectionStarting( sectionInfo ); - } - - void testCaseStarting( TestCaseInfo const& testInfo ) override { - m_testTimer.start(); - StreamingReporterBase::testCaseStarting( testInfo ); - stream << "##teamcity[testStarted name='" - << escape( testInfo.name ) << "']\n"; - stream.flush(); - } - - void testCaseEnded( TestCaseStats const& testCaseStats ) override { - StreamingReporterBase::testCaseEnded( testCaseStats ); - if( !testCaseStats.stdOut.empty() ) - stream << "##teamcity[testStdOut name='" - << escape( testCaseStats.testInfo.name ) - << "' out='" << escape( testCaseStats.stdOut ) << "']\n"; - if( !testCaseStats.stdErr.empty() ) - stream << "##teamcity[testStdErr name='" - << escape( testCaseStats.testInfo.name ) - << "' out='" << escape( testCaseStats.stdErr ) << "']\n"; - stream << "##teamcity[testFinished name='" - << escape( testCaseStats.testInfo.name ) << "' duration='" - << m_testTimer.getElapsedMilliseconds() << "']\n"; - stream.flush(); - } - - private: - void printSectionHeader( std::ostream& os ) { - assert( !m_sectionStack.empty() ); - - if( m_sectionStack.size() > 1 ) { - os << getLineOfChars<'-'>() << "\n"; - - std::vector::const_iterator - it = m_sectionStack.begin()+1, // Skip first section (test case) - itEnd = m_sectionStack.end(); - for( ; it != itEnd; ++it ) - printHeaderString( os, it->name ); - os << getLineOfChars<'-'>() << "\n"; - } - - SourceLineInfo lineInfo = m_sectionStack.front().lineInfo; - - os << lineInfo << "\n"; - os << getLineOfChars<'.'>() << "\n\n"; - } - - // if string has a : in first line will set indent to follow it on - // subsequent lines - static void printHeaderString( std::ostream& os, std::string const& _string, std::size_t indent = 0 ) { - std::size_t i = _string.find( ": " ); - if( i != std::string::npos ) - i+=2; - else - i = 0; - os << Column( _string ) - .indent( indent+i) - .initialIndent( indent ) << "\n"; - } - private: - bool m_headerPrintedForThisSection = false; - Timer m_testTimer; - }; - -#ifdef CATCH_IMPL - TeamCityReporter::~TeamCityReporter() {} -#endif - - CATCH_REGISTER_REPORTER( "teamcity", TeamCityReporter ) - -} // end namespace Catch - -#ifdef __clang__ -# pragma clang diagnostic pop -#endif - -#endif // TWOBLUECUBES_CATCH_REPORTER_TEAMCITY_HPP_INCLUDED diff --git a/third_party/json11/json11.cpp b/third_party/json11/json11.cpp deleted file mode 100644 index 3bd4fde2f2..0000000000 --- a/third_party/json11/json11.cpp +++ /dev/null @@ -1,785 +0,0 @@ -/* Copyright (c) 2013 Dropbox, Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - */ - -#include "json11.hpp" -#include -#include -#include -#include -#include -#include - -namespace json11 { - -static const int max_depth = 200; - -using std::string; -using std::vector; -using std::map; -using std::make_shared; -using std::initializer_list; -using std::move; - -/* Helper for representing null - just a do-nothing struct, plus comparison - * operators so the helpers in JsonValue work. We can't use nullptr_t because - * it may not be orderable. - */ -struct NullStruct { - bool operator==(NullStruct) const { return true; } - bool operator<(NullStruct) const { return false; } -}; - -/* * * * * * * * * * * * * * * * * * * * - * Serialization - */ - -static void dump(NullStruct, string &out) { - out += "null"; -} - -static void dump(double value, string &out) { - if (std::isfinite(value)) { - char buf[32]; - snprintf(buf, sizeof buf, "%.17g", value); - out += buf; - } else { - out += "null"; - } -} - -static void dump(int value, string &out) { - char buf[32]; - snprintf(buf, sizeof buf, "%d", value); - out += buf; -} - -static void dump(bool value, string &out) { - out += value ? "true" : "false"; -} - -static void dump(const string &value, string &out) { - out += '"'; - for (size_t i = 0; i < value.length(); i++) { - const char ch = value[i]; - if (ch == '\\') { - out += "\\\\"; - } else if (ch == '"') { - out += "\\\""; - } else if (ch == '\b') { - out += "\\b"; - } else if (ch == '\f') { - out += "\\f"; - } else if (ch == '\n') { - out += "\\n"; - } else if (ch == '\r') { - out += "\\r"; - } else if (ch == '\t') { - out += "\\t"; - } else if (static_cast(ch) <= 0x1f) { - char buf[8]; - snprintf(buf, sizeof buf, "\\u%04x", ch); - out += buf; - } else if (static_cast(ch) == 0xe2 && static_cast(value[i+1]) == 0x80 - && static_cast(value[i+2]) == 0xa8) { - out += "\\u2028"; - i += 2; - } else if (static_cast(ch) == 0xe2 && static_cast(value[i+1]) == 0x80 - && static_cast(value[i+2]) == 0xa9) { - out += "\\u2029"; - i += 2; - } else { - out += ch; - } - } - out += '"'; -} - -static void dump(const Json::array &values, string &out) { - bool first = true; - out += "["; - for (const auto &value : values) { - if (!first) - out += ", "; - value.dump(out); - first = false; - } - out += "]"; -} - -static void dump(const Json::object &values, string &out) { - bool first = true; - out += "{"; - for (const auto &kv : values) { - if (!first) - out += ", "; - dump(kv.first, out); - out += ": "; - kv.second.dump(out); - first = false; - } - out += "}"; -} - -void Json::dump(string &out) const { - m_ptr->dump(out); -} - -/* * * * * * * * * * * * * * * * * * * * - * Value wrappers - */ - -template -class Value : public JsonValue { -protected: - - // Constructors - explicit Value(const T &value) : m_value(value) {} - explicit Value(T &&value) : m_value(move(value)) {} - - // Get type tag - Json::Type type() const override { - return tag; - } - - // Comparisons - bool equals(const JsonValue * other) const override { - return m_value == static_cast *>(other)->m_value; - } - bool less(const JsonValue * other) const override { - return m_value < static_cast *>(other)->m_value; - } - - const T m_value; - void dump(string &out) const override { json11::dump(m_value, out); } -}; - -class JsonDouble final : public Value { - double number_value() const override { return m_value; } - int int_value() const override { return static_cast(m_value); } - bool equals(const JsonValue * other) const override { return m_value == other->number_value(); } - bool less(const JsonValue * other) const override { return m_value < other->number_value(); } -public: - explicit JsonDouble(double value) : Value(value) {} -}; - -class JsonInt final : public Value { - double number_value() const override { return m_value; } - int int_value() const override { return m_value; } - bool equals(const JsonValue * other) const override { return m_value == other->number_value(); } - bool less(const JsonValue * other) const override { return m_value < other->number_value(); } -public: - explicit JsonInt(int value) : Value(value) {} -}; - -class JsonBoolean final : public Value { - bool bool_value() const override { return m_value; } -public: - explicit JsonBoolean(bool value) : Value(value) {} -}; - -class JsonString final : public Value { - const string &string_value() const override { return m_value; } -public: - explicit JsonString(const string &value) : Value(value) {} - explicit JsonString(string &&value) : Value(move(value)) {} -}; - -class JsonArray final : public Value { - const Json::array &array_items() const override { return m_value; } - const Json & operator[](size_t i) const override; -public: - explicit JsonArray(const Json::array &value) : Value(value) {} - explicit JsonArray(Json::array &&value) : Value(move(value)) {} -}; - -class JsonObject final : public Value { - const Json::object &object_items() const override { return m_value; } - const Json & operator[](const string &key) const override; -public: - explicit JsonObject(const Json::object &value) : Value(value) {} - explicit JsonObject(Json::object &&value) : Value(move(value)) {} -}; - -class JsonNull final : public Value { -public: - JsonNull() : Value({}) {} -}; - -/* * * * * * * * * * * * * * * * * * * * - * Static globals - static-init-safe - */ -struct Statics { - const std::shared_ptr null = make_shared(); - const std::shared_ptr t = make_shared(true); - const std::shared_ptr f = make_shared(false); - const string empty_string; - const vector empty_vector; - const map empty_map; - Statics() {} -}; - -static const Statics & statics() { - static const Statics s {}; - return s; -} - -static const Json & static_null() { - // This has to be separate, not in Statics, because Json() accesses statics().null. - static const Json json_null; - return json_null; -} - -/* * * * * * * * * * * * * * * * * * * * - * Constructors - */ - -Json::Json() noexcept : m_ptr(statics().null) {} -Json::Json(std::nullptr_t) noexcept : m_ptr(statics().null) {} -Json::Json(double value) : m_ptr(make_shared(value)) {} -Json::Json(int value) : m_ptr(make_shared(value)) {} -Json::Json(bool value) : m_ptr(value ? statics().t : statics().f) {} -Json::Json(const string &value) : m_ptr(make_shared(value)) {} -Json::Json(string &&value) : m_ptr(make_shared(move(value))) {} -Json::Json(const char * value) : m_ptr(make_shared(value)) {} -Json::Json(const Json::array &values) : m_ptr(make_shared(values)) {} -Json::Json(Json::array &&values) : m_ptr(make_shared(move(values))) {} -Json::Json(const Json::object &values) : m_ptr(make_shared(values)) {} -Json::Json(Json::object &&values) : m_ptr(make_shared(move(values))) {} - -/* * * * * * * * * * * * * * * * * * * * - * Accessors - */ - -Json::Type Json::type() const { return m_ptr->type(); } -double Json::number_value() const { return m_ptr->number_value(); } -int Json::int_value() const { return m_ptr->int_value(); } -bool Json::bool_value() const { return m_ptr->bool_value(); } -const string & Json::string_value() const { return m_ptr->string_value(); } -const vector & Json::array_items() const { return m_ptr->array_items(); } -const map & Json::object_items() const { return m_ptr->object_items(); } -const Json & Json::operator[] (size_t i) const { return (*m_ptr)[i]; } -const Json & Json::operator[] (const string &key) const { return (*m_ptr)[key]; } - -double JsonValue::number_value() const { return 0; } -int JsonValue::int_value() const { return 0; } -bool JsonValue::bool_value() const { return false; } -const string & JsonValue::string_value() const { return statics().empty_string; } -const vector & JsonValue::array_items() const { return statics().empty_vector; } -const map & JsonValue::object_items() const { return statics().empty_map; } -const Json & JsonValue::operator[] (size_t) const { return static_null(); } -const Json & JsonValue::operator[] (const string &) const { return static_null(); } - -const Json & JsonObject::operator[] (const string &key) const { - auto iter = m_value.find(key); - return (iter == m_value.end()) ? static_null() : iter->second; -} -const Json & JsonArray::operator[] (size_t i) const { - if (i >= m_value.size()) return static_null(); - else return m_value[i]; -} - -/* * * * * * * * * * * * * * * * * * * * - * Comparison - */ - -bool Json::operator== (const Json &other) const { - if (m_ptr->type() != other.m_ptr->type()) - return false; - - return m_ptr->equals(other.m_ptr.get()); -} - -bool Json::operator< (const Json &other) const { - if (m_ptr->type() != other.m_ptr->type()) - return m_ptr->type() < other.m_ptr->type(); - - return m_ptr->less(other.m_ptr.get()); -} - -/* * * * * * * * * * * * * * * * * * * * - * Parsing - */ - -/* esc(c) - * - * Format char c suitable for printing in an error message. - */ -static inline string esc(char c) { - char buf[12]; - if (static_cast(c) >= 0x20 && static_cast(c) <= 0x7f) { - snprintf(buf, sizeof buf, "'%c' (%d)", c, c); - } else { - snprintf(buf, sizeof buf, "(%d)", c); - } - return string(buf); -} - -static inline bool in_range(long x, long lower, long upper) { - return (x >= lower && x <= upper); -} - -namespace { -/* JsonParser - * - * Object that tracks all state of an in-progress parse. - */ -struct JsonParser final { - - /* State - */ - const string &str; - size_t i; - string &err; - bool failed; - const JsonParse strategy; - - /* fail(msg, err_ret = Json()) - * - * Mark this parse as failed. - */ - Json fail(string &&msg) { - return fail(move(msg), Json()); - } - - template - T fail(string &&msg, const T err_ret) { - if (!failed) - err = std::move(msg); - failed = true; - return err_ret; - } - - /* consume_whitespace() - * - * Advance until the current character is non-whitespace. - */ - void consume_whitespace() { - while (str[i] == ' ' || str[i] == '\r' || str[i] == '\n' || str[i] == '\t') - i++; - } - - /* consume_comment() - * - * Advance comments (c-style inline and multiline). - */ - bool consume_comment() { - bool comment_found = false; - if (str[i] == '/') { - i++; - if (i == str.size()) - return fail("unexpected end of input after start of comment", false); - if (str[i] == '/') { // inline comment - i++; - // advance until next line, or end of input - while (i < str.size() && str[i] != '\n') { - i++; - } - comment_found = true; - } - else if (str[i] == '*') { // multiline comment - i++; - if (i > str.size()-2) - return fail("unexpected end of input inside multi-line comment", false); - // advance until closing tokens - while (!(str[i] == '*' && str[i+1] == '/')) { - i++; - if (i > str.size()-2) - return fail( - "unexpected end of input inside multi-line comment", false); - } - i += 2; - comment_found = true; - } - else - return fail("malformed comment", false); - } - return comment_found; - } - - /* consume_garbage() - * - * Advance until the current character is non-whitespace and non-comment. - */ - void consume_garbage() { - consume_whitespace(); - if(strategy == JsonParse::COMMENTS) { - bool comment_found = false; - do { - comment_found = consume_comment(); - if (failed) return; - consume_whitespace(); - } - while(comment_found); - } - } - - /* get_next_token() - * - * Return the next non-whitespace character. If the end of the input is reached, - * flag an error and return 0. - */ - char get_next_token() { - consume_garbage(); - if (failed) return (char)0; - if (i == str.size()) - return fail("unexpected end of input", (char)0); - - return str[i++]; - } - - /* encode_utf8(pt, out) - * - * Encode pt as UTF-8 and add it to out. - */ - void encode_utf8(long pt, string & out) { - if (pt < 0) - return; - - if (pt < 0x80) { - out += static_cast(pt); - } else if (pt < 0x800) { - out += static_cast((pt >> 6) | 0xC0); - out += static_cast((pt & 0x3F) | 0x80); - } else if (pt < 0x10000) { - out += static_cast((pt >> 12) | 0xE0); - out += static_cast(((pt >> 6) & 0x3F) | 0x80); - out += static_cast((pt & 0x3F) | 0x80); - } else { - out += static_cast((pt >> 18) | 0xF0); - out += static_cast(((pt >> 12) & 0x3F) | 0x80); - out += static_cast(((pt >> 6) & 0x3F) | 0x80); - out += static_cast((pt & 0x3F) | 0x80); - } - } - - /* parse_string() - * - * Parse a string, starting at the current position. - */ - string parse_string() { - string out; - long last_escaped_codepoint = -1; - while (true) { - if (i == str.size()) - return fail("unexpected end of input in string", ""); - - char ch = str[i++]; - - if (ch == '"') { - encode_utf8(last_escaped_codepoint, out); - return out; - } - - if (in_range(ch, 0, 0x1f)) - return fail("unescaped " + esc(ch) + " in string", ""); - - // The usual case: non-escaped characters - if (ch != '\\') { - encode_utf8(last_escaped_codepoint, out); - last_escaped_codepoint = -1; - out += ch; - continue; - } - - // Handle escapes - if (i == str.size()) - return fail("unexpected end of input in string", ""); - - ch = str[i++]; - - if (ch == 'u') { - // Extract 4-byte escape sequence - string esc = str.substr(i, 4); - // Explicitly check length of the substring. The following loop - // relies on std::string returning the terminating NUL when - // accessing str[length]. Checking here reduces brittleness. - if (esc.length() < 4) { - return fail("bad \\u escape: " + esc, ""); - } - for (size_t j = 0; j < 4; j++) { - if (!in_range(esc[j], 'a', 'f') && !in_range(esc[j], 'A', 'F') - && !in_range(esc[j], '0', '9')) - return fail("bad \\u escape: " + esc, ""); - } - - long codepoint = strtol(esc.data(), nullptr, 16); - - // JSON specifies that characters outside the BMP shall be encoded as a pair - // of 4-hex-digit \u escapes encoding their surrogate pair components. Check - // whether we're in the middle of such a beast: the previous codepoint was an - // escaped lead (high) surrogate, and this is a trail (low) surrogate. - if (in_range(last_escaped_codepoint, 0xD800, 0xDBFF) - && in_range(codepoint, 0xDC00, 0xDFFF)) { - // Reassemble the two surrogate pairs into one astral-plane character, per - // the UTF-16 algorithm. - encode_utf8((((last_escaped_codepoint - 0xD800) << 10) - | (codepoint - 0xDC00)) + 0x10000, out); - last_escaped_codepoint = -1; - } else { - encode_utf8(last_escaped_codepoint, out); - last_escaped_codepoint = codepoint; - } - - i += 4; - continue; - } - - encode_utf8(last_escaped_codepoint, out); - last_escaped_codepoint = -1; - - if (ch == 'b') { - out += '\b'; - } else if (ch == 'f') { - out += '\f'; - } else if (ch == 'n') { - out += '\n'; - } else if (ch == 'r') { - out += '\r'; - } else if (ch == 't') { - out += '\t'; - } else if (ch == '"' || ch == '\\' || ch == '/') { - out += ch; - } else { - return fail("invalid escape character " + esc(ch), ""); - } - } - } - - /* parse_number() - * - * Parse a double. - */ - Json parse_number() { - size_t start_pos = i; - - if (str[i] == '-') - i++; - - // Integer part - if (str[i] == '0') { - i++; - if (in_range(str[i], '0', '9')) - return fail("leading 0s not permitted in numbers"); - } else if (in_range(str[i], '1', '9')) { - i++; - while (in_range(str[i], '0', '9')) - i++; - } else { - return fail("invalid " + esc(str[i]) + " in number"); - } - - if (str[i] != '.' && str[i] != 'e' && str[i] != 'E' - && (i - start_pos) <= static_cast(std::numeric_limits::digits10)) { - return std::atoi(str.c_str() + start_pos); - } - - // Decimal part - if (str[i] == '.') { - i++; - if (!in_range(str[i], '0', '9')) - return fail("at least one digit required in fractional part"); - - while (in_range(str[i], '0', '9')) - i++; - } - - // Exponent part - if (str[i] == 'e' || str[i] == 'E') { - i++; - - if (str[i] == '+' || str[i] == '-') - i++; - - if (!in_range(str[i], '0', '9')) - return fail("at least one digit required in exponent"); - - while (in_range(str[i], '0', '9')) - i++; - } - - return std::strtod(str.c_str() + start_pos, nullptr); - } - - /* expect(str, res) - * - * Expect that 'str' starts at the character that was just read. If it does, advance - * the input and return res. If not, flag an error. - */ - Json expect(const string &expected, Json res) { - assert(i != 0); - i--; - if (str.compare(i, expected.length(), expected) == 0) { - i += expected.length(); - return res; - } else { - return fail("parse error: expected " + expected + ", got " + str.substr(i, expected.length())); - } - } - - /* parse_json() - * - * Parse a JSON object. - */ - Json parse_json(int depth) { - if (depth > max_depth) { - return fail("exceeded maximum nesting depth"); - } - - char ch = get_next_token(); - if (failed) - return Json(); - - if (ch == '-' || (ch >= '0' && ch <= '9')) { - i--; - return parse_number(); - } - - if (ch == 't') - return expect("true", true); - - if (ch == 'f') - return expect("false", false); - - if (ch == 'n') - return expect("null", Json()); - - if (ch == '"') - return parse_string(); - - if (ch == '{') { - map data; - ch = get_next_token(); - if (ch == '}') - return data; - - while (1) { - if (ch != '"') - return fail("expected '\"' in object, got " + esc(ch)); - - string key = parse_string(); - if (failed) - return Json(); - - ch = get_next_token(); - if (ch != ':') - return fail("expected ':' in object, got " + esc(ch)); - - data[std::move(key)] = parse_json(depth + 1); - if (failed) - return Json(); - - ch = get_next_token(); - if (ch == '}') - break; - if (ch != ',') - return fail("expected ',' in object, got " + esc(ch)); - - ch = get_next_token(); - } - return data; - } - - if (ch == '[') { - vector data; - ch = get_next_token(); - if (ch == ']') - return data; - - while (1) { - i--; - data.push_back(parse_json(depth + 1)); - if (failed) - return Json(); - - ch = get_next_token(); - if (ch == ']') - break; - if (ch != ',') - return fail("expected ',' in list, got " + esc(ch)); - - ch = get_next_token(); - (void)ch; - } - return data; - } - - return fail("expected value, got " + esc(ch)); - } -}; -}//namespace { - -Json Json::parse(const string &in, string &err, JsonParse strategy) { - JsonParser parser { in, 0, err, false, strategy }; - Json result = parser.parse_json(0); - - // Check for any trailing garbage - parser.consume_garbage(); - if (parser.failed) - return Json(); - if (parser.i != in.size()) - return parser.fail("unexpected trailing " + esc(in[parser.i])); - - return result; -} - -// Documented in json11.hpp -vector Json::parse_multi(const string &in, - std::string::size_type &parser_stop_pos, - string &err, - JsonParse strategy) { - JsonParser parser { in, 0, err, false, strategy }; - parser_stop_pos = 0; - vector json_vec; - while (parser.i != in.size() && !parser.failed) { - json_vec.push_back(parser.parse_json(0)); - if (parser.failed) - break; - - // Check for another object - parser.consume_garbage(); - if (parser.failed) - break; - parser_stop_pos = parser.i; - } - return json_vec; -} - -/* * * * * * * * * * * * * * * * * * * * - * Shape-checking - */ - -bool Json::has_shape(const shape & types, string & err) const { - if (!is_object()) { - err = "expected JSON object, got " + dump(); - return false; - } - - for (auto & item : types) { - if ((*this)[item.first].type() != item.second) { - err = "bad type for " + item.first + " in " + dump(); - return false; - } - } - - return true; -} - -} // namespace json11 diff --git a/third_party/json11/json11.hpp b/third_party/json11/json11.hpp deleted file mode 100644 index 5202ef9323..0000000000 --- a/third_party/json11/json11.hpp +++ /dev/null @@ -1,232 +0,0 @@ -/* json11 - * - * json11 is a tiny JSON library for C++11, providing JSON parsing and serialization. - * - * The core object provided by the library is json11::Json. A Json object represents any JSON - * value: null, bool, number (int or double), string (std::string), array (std::vector), or - * object (std::map). - * - * Json objects act like values: they can be assigned, copied, moved, compared for equality or - * order, etc. There are also helper methods Json::dump, to serialize a Json to a string, and - * Json::parse (static) to parse a std::string as a Json object. - * - * Internally, the various types of Json object are represented by the JsonValue class - * hierarchy. - * - * A note on numbers - JSON specifies the syntax of number formatting but not its semantics, - * so some JSON implementations distinguish between integers and floating-point numbers, while - * some don't. In json11, we choose the latter. Because some JSON implementations (namely - * Javascript itself) treat all numbers as the same type, distinguishing the two leads - * to JSON that will be *silently* changed by a round-trip through those implementations. - * Dangerous! To avoid that risk, json11 stores all numbers as double internally, but also - * provides integer helpers. - * - * Fortunately, double-precision IEEE754 ('double') can precisely store any integer in the - * range +/-2^53, which includes every 'int' on most systems. (Timestamps often use int64 - * or long long to avoid the Y2038K problem; a double storing microseconds since some epoch - * will be exact for +/- 275 years.) - */ - -/* Copyright (c) 2013 Dropbox, Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - */ - -#pragma once - -#include -#include -#include -#include -#include - -#ifdef _MSC_VER - #if _MSC_VER <= 1800 // VS 2013 - #ifndef noexcept - #define noexcept throw() - #endif - - #ifndef snprintf - #define snprintf _snprintf_s - #endif - #endif -#endif - -namespace json11 { - -enum JsonParse { - STANDARD, COMMENTS -}; - -class JsonValue; - -class Json final { -public: - // Types - enum Type { - NUL, NUMBER, BOOL, STRING, ARRAY, OBJECT - }; - - // Array and object typedefs - typedef std::vector array; - typedef std::map object; - - // Constructors for the various types of JSON value. - Json() noexcept; // NUL - Json(std::nullptr_t) noexcept; // NUL - Json(double value); // NUMBER - Json(int value); // NUMBER - Json(bool value); // BOOL - Json(const std::string &value); // STRING - Json(std::string &&value); // STRING - Json(const char * value); // STRING - Json(const array &values); // ARRAY - Json(array &&values); // ARRAY - Json(const object &values); // OBJECT - Json(object &&values); // OBJECT - - // Implicit constructor: anything with a to_json() function. - template - Json(const T & t) : Json(t.to_json()) {} - - // Implicit constructor: map-like objects (std::map, std::unordered_map, etc) - template ::value - && std::is_constructible::value, - int>::type = 0> - Json(const M & m) : Json(object(m.begin(), m.end())) {} - - // Implicit constructor: vector-like objects (std::list, std::vector, std::set, etc) - template ::value, - int>::type = 0> - Json(const V & v) : Json(array(v.begin(), v.end())) {} - - // This prevents Json(some_pointer) from accidentally producing a bool. Use - // Json(bool(some_pointer)) if that behavior is desired. - Json(void *) = delete; - - // Accessors - Type type() const; - - bool is_null() const { return type() == NUL; } - bool is_number() const { return type() == NUMBER; } - bool is_bool() const { return type() == BOOL; } - bool is_string() const { return type() == STRING; } - bool is_array() const { return type() == ARRAY; } - bool is_object() const { return type() == OBJECT; } - - // Return the enclosed value if this is a number, 0 otherwise. Note that json11 does not - // distinguish between integer and non-integer numbers - number_value() and int_value() - // can both be applied to a NUMBER-typed object. - double number_value() const; - int int_value() const; - - // Return the enclosed value if this is a boolean, false otherwise. - bool bool_value() const; - // Return the enclosed string if this is a string, "" otherwise. - const std::string &string_value() const; - // Return the enclosed std::vector if this is an array, or an empty vector otherwise. - const array &array_items() const; - // Return the enclosed std::map if this is an object, or an empty map otherwise. - const object &object_items() const; - - // Return a reference to arr[i] if this is an array, Json() otherwise. - const Json & operator[](size_t i) const; - // Return a reference to obj[key] if this is an object, Json() otherwise. - const Json & operator[](const std::string &key) const; - - // Serialize. - void dump(std::string &out) const; - std::string dump() const { - std::string out; - dump(out); - return out; - } - - // Parse. If parse fails, return Json() and assign an error message to err. - static Json parse(const std::string & in, - std::string & err, - JsonParse strategy = JsonParse::STANDARD); - static Json parse(const char * in, - std::string & err, - JsonParse strategy = JsonParse::STANDARD) { - if (in) { - return parse(std::string(in), err, strategy); - } else { - err = "null input"; - return nullptr; - } - } - // Parse multiple objects, concatenated or separated by whitespace - static std::vector parse_multi( - const std::string & in, - std::string::size_type & parser_stop_pos, - std::string & err, - JsonParse strategy = JsonParse::STANDARD); - - static inline std::vector parse_multi( - const std::string & in, - std::string & err, - JsonParse strategy = JsonParse::STANDARD) { - std::string::size_type parser_stop_pos; - return parse_multi(in, parser_stop_pos, err, strategy); - } - - bool operator== (const Json &rhs) const; - bool operator< (const Json &rhs) const; - bool operator!= (const Json &rhs) const { return !(*this == rhs); } - bool operator<= (const Json &rhs) const { return !(rhs < *this); } - bool operator> (const Json &rhs) const { return (rhs < *this); } - bool operator>= (const Json &rhs) const { return !(*this < rhs); } - - /* has_shape(types, err) - * - * Return true if this is a JSON object and, for each item in types, has a field of - * the given type. If not, return false and set err to a descriptive message. - */ - typedef std::initializer_list> shape; - bool has_shape(const shape & types, std::string & err) const; - -private: - std::shared_ptr m_ptr; -}; - -// Internal class hierarchy - JsonValue objects are not exposed to users of this API. -class JsonValue { -protected: - friend class Json; - friend class JsonInt; - friend class JsonDouble; - virtual Json::Type type() const = 0; - virtual bool equals(const JsonValue * other) const = 0; - virtual bool less(const JsonValue * other) const = 0; - virtual void dump(std::string &out) const = 0; - virtual double number_value() const; - virtual int int_value() const; - virtual bool bool_value() const; - virtual const std::string &string_value() const; - virtual const Json::array &array_items() const; - virtual const Json &operator[](size_t i) const; - virtual const Json::object &object_items() const; - virtual const Json &operator[](const std::string &key) const; - virtual ~JsonValue() {} -}; - -} // namespace json11 diff --git a/third_party/linux/include/linux/ion.h b/third_party/linux/include/linux/ion.h deleted file mode 100644 index 7b5b031f57..0000000000 --- a/third_party/linux/include/linux/ion.h +++ /dev/null @@ -1,78 +0,0 @@ -/**************************************************************************** - **************************************************************************** - *** - *** This header was automatically generated from a Linux kernel header - *** of the same name, to make information necessary for userspace to - *** call into the kernel available to libc. It contains only constants, - *** structures, and macros generated from the original header, and thus, - *** contains no copyrightable information. - *** - *** To edit the content of this header, modify the corresponding - *** source file (e.g. under external/kernel-headers/original/) then - *** run bionic/libc/kernel/tools/update_all.py - *** - *** Any manual change here will be lost the next time this script will - *** be run. You've been warned! - *** - **************************************************************************** - ****************************************************************************/ -#ifndef _UAPI_LINUX_ION_H -#define _UAPI_LINUX_ION_H -#include -#include -typedef int ion_user_handle_t; -enum ion_heap_type { - ION_HEAP_TYPE_SYSTEM, - ION_HEAP_TYPE_SYSTEM_CONTIG, - ION_HEAP_TYPE_CARVEOUT, - ION_HEAP_TYPE_CHUNK, - ION_HEAP_TYPE_DMA, - ION_HEAP_TYPE_CUSTOM, -}; -#define ION_NUM_HEAP_IDS (sizeof(unsigned int) * 8) -#define ION_FLAG_CACHED 1 -#define ION_FLAG_CACHED_NEEDS_SYNC 2 -struct ion_allocation_data { - size_t len; - size_t align; - unsigned int heap_id_mask; - unsigned int flags; - ion_user_handle_t handle; -}; -struct ion_fd_data { - ion_user_handle_t handle; - int fd; -}; -struct ion_handle_data { - ion_user_handle_t handle; -}; -struct ion_custom_data { - unsigned int cmd; - unsigned long arg; -}; -#define MAX_HEAP_NAME 32 -struct ion_heap_data { - char name[MAX_HEAP_NAME]; - __u32 type; - __u32 heap_id; - __u32 reserved0; - __u32 reserved1; - __u32 reserved2; -}; -struct ion_heap_query { - __u32 cnt; - __u32 reserved0; - __u64 heaps; - __u32 reserved1; - __u32 reserved2; -}; -#define ION_IOC_MAGIC 'I' -#define ION_IOC_ALLOC _IOWR(ION_IOC_MAGIC, 0, struct ion_allocation_data) -#define ION_IOC_FREE _IOWR(ION_IOC_MAGIC, 1, struct ion_handle_data) -#define ION_IOC_MAP _IOWR(ION_IOC_MAGIC, 2, struct ion_fd_data) -#define ION_IOC_SHARE _IOWR(ION_IOC_MAGIC, 4, struct ion_fd_data) -#define ION_IOC_IMPORT _IOWR(ION_IOC_MAGIC, 5, struct ion_fd_data) -#define ION_IOC_SYNC _IOWR(ION_IOC_MAGIC, 7, struct ion_fd_data) -#define ION_IOC_CUSTOM _IOWR(ION_IOC_MAGIC, 6, struct ion_custom_data) -#define ION_IOC_HEAP_QUERY _IOWR(ION_IOC_MAGIC, 8, struct ion_heap_query) -#endif diff --git a/third_party/linux/include/media/cam_cpas.h b/third_party/linux/include/media/cam_cpas.h deleted file mode 100644 index c5cbac82e7..0000000000 --- a/third_party/linux/include/media/cam_cpas.h +++ /dev/null @@ -1,25 +0,0 @@ -#ifndef __UAPI_CAM_CPAS_H__ -#define __UAPI_CAM_CPAS_H__ - -#include "cam_defs.h" - -#define CAM_FAMILY_CAMERA_SS 1 -#define CAM_FAMILY_CPAS_SS 2 - -/** - * struct cam_cpas_query_cap - CPAS query device capability payload - * - * @camera_family : Camera family type - * @reserved : Reserved field for alignment - * @camera_version : Camera platform version - * @cpas_version : Camera CPAS version within camera platform - * - */ -struct cam_cpas_query_cap { - uint32_t camera_family; - uint32_t reserved; - struct cam_hw_version camera_version; - struct cam_hw_version cpas_version; -}; - -#endif /* __UAPI_CAM_CPAS_H__ */ diff --git a/third_party/linux/include/media/cam_defs.h b/third_party/linux/include/media/cam_defs.h deleted file mode 100644 index e006463d2a..0000000000 --- a/third_party/linux/include/media/cam_defs.h +++ /dev/null @@ -1,477 +0,0 @@ -#ifndef __UAPI_CAM_DEFS_H__ -#define __UAPI_CAM_DEFS_H__ - -#include -#include -#include - - -/* camera op codes */ -#define CAM_COMMON_OPCODE_BASE 0x100 -#define CAM_QUERY_CAP (CAM_COMMON_OPCODE_BASE + 0x1) -#define CAM_ACQUIRE_DEV (CAM_COMMON_OPCODE_BASE + 0x2) -#define CAM_START_DEV (CAM_COMMON_OPCODE_BASE + 0x3) -#define CAM_STOP_DEV (CAM_COMMON_OPCODE_BASE + 0x4) -#define CAM_CONFIG_DEV (CAM_COMMON_OPCODE_BASE + 0x5) -#define CAM_RELEASE_DEV (CAM_COMMON_OPCODE_BASE + 0x6) -#define CAM_SD_SHUTDOWN (CAM_COMMON_OPCODE_BASE + 0x7) -#define CAM_FLUSH_REQ (CAM_COMMON_OPCODE_BASE + 0x8) -#define CAM_COMMON_OPCODE_MAX (CAM_COMMON_OPCODE_BASE + 0x9) - -#define CAM_EXT_OPCODE_BASE 0x200 -#define CAM_CONFIG_DEV_EXTERNAL (CAM_EXT_OPCODE_BASE + 0x1) - -/* camera handle type */ -#define CAM_HANDLE_USER_POINTER 1 -#define CAM_HANDLE_MEM_HANDLE 2 - -/* Generic Blob CmdBuffer header properties */ -#define CAM_GENERIC_BLOB_CMDBUFFER_SIZE_MASK 0xFFFFFF00 -#define CAM_GENERIC_BLOB_CMDBUFFER_SIZE_SHIFT 8 -#define CAM_GENERIC_BLOB_CMDBUFFER_TYPE_MASK 0xFF -#define CAM_GENERIC_BLOB_CMDBUFFER_TYPE_SHIFT 0 - -/* Command Buffer Types */ -#define CAM_CMD_BUF_DMI 0x1 -#define CAM_CMD_BUF_DMI16 0x2 -#define CAM_CMD_BUF_DMI32 0x3 -#define CAM_CMD_BUF_DMI64 0x4 -#define CAM_CMD_BUF_DIRECT 0x5 -#define CAM_CMD_BUF_INDIRECT 0x6 -#define CAM_CMD_BUF_I2C 0x7 -#define CAM_CMD_BUF_FW 0x8 -#define CAM_CMD_BUF_GENERIC 0x9 -#define CAM_CMD_BUF_LEGACY 0xA - -/** - * enum flush_type_t - Identifies the various flush types - * - * @CAM_FLUSH_TYPE_REQ: Flush specific request - * @CAM_FLUSH_TYPE_ALL: Flush all requests belonging to a context - * @CAM_FLUSH_TYPE_MAX: Max enum to validate flush type - * - */ -enum flush_type_t { - CAM_FLUSH_TYPE_REQ, - CAM_FLUSH_TYPE_ALL, - CAM_FLUSH_TYPE_MAX -}; - -/** - * struct cam_control - Structure used by ioctl control for camera - * - * @op_code: This is the op code for camera control - * @size: Control command size - * @handle_type: User pointer or shared memory handle - * @reserved: Reserved field for 64 bit alignment - * @handle: Control command payload - */ -struct cam_control { - uint32_t op_code; - uint32_t size; - uint32_t handle_type; - uint32_t reserved; - uint64_t handle; -}; - -/* camera IOCTL */ -#define VIDIOC_CAM_CONTROL \ - _IOWR('V', BASE_VIDIOC_PRIVATE, struct cam_control) - -/** - * struct cam_hw_version - Structure for HW version of camera devices - * - * @major : Hardware version major - * @minor : Hardware version minor - * @incr : Hardware version increment - * @reserved : Reserved for 64 bit aligngment - */ -struct cam_hw_version { - uint32_t major; - uint32_t minor; - uint32_t incr; - uint32_t reserved; -}; - -/** - * struct cam_iommu_handle - Structure for IOMMU handles of camera hw devices - * - * @non_secure: Device Non Secure IOMMU handle - * @secure: Device Secure IOMMU handle - * - */ -struct cam_iommu_handle { - int32_t non_secure; - int32_t secure; -}; - -/* camera secure mode */ -#define CAM_SECURE_MODE_NON_SECURE 0 -#define CAM_SECURE_MODE_SECURE 1 - -/* Camera Format Type */ -#define CAM_FORMAT_BASE 0 -#define CAM_FORMAT_MIPI_RAW_6 1 -#define CAM_FORMAT_MIPI_RAW_8 2 -#define CAM_FORMAT_MIPI_RAW_10 3 -#define CAM_FORMAT_MIPI_RAW_12 4 -#define CAM_FORMAT_MIPI_RAW_14 5 -#define CAM_FORMAT_MIPI_RAW_16 6 -#define CAM_FORMAT_MIPI_RAW_20 7 -#define CAM_FORMAT_QTI_RAW_8 8 -#define CAM_FORMAT_QTI_RAW_10 9 -#define CAM_FORMAT_QTI_RAW_12 10 -#define CAM_FORMAT_QTI_RAW_14 11 -#define CAM_FORMAT_PLAIN8 12 -#define CAM_FORMAT_PLAIN16_8 13 -#define CAM_FORMAT_PLAIN16_10 14 -#define CAM_FORMAT_PLAIN16_12 15 -#define CAM_FORMAT_PLAIN16_14 16 -#define CAM_FORMAT_PLAIN16_16 17 -#define CAM_FORMAT_PLAIN32_20 18 -#define CAM_FORMAT_PLAIN64 19 -#define CAM_FORMAT_PLAIN128 20 -#define CAM_FORMAT_ARGB 21 -#define CAM_FORMAT_ARGB_10 22 -#define CAM_FORMAT_ARGB_12 23 -#define CAM_FORMAT_ARGB_14 24 -#define CAM_FORMAT_DPCM_10_6_10 25 -#define CAM_FORMAT_DPCM_10_8_10 26 -#define CAM_FORMAT_DPCM_12_6_12 27 -#define CAM_FORMAT_DPCM_12_8_12 28 -#define CAM_FORMAT_DPCM_14_8_14 29 -#define CAM_FORMAT_DPCM_14_10_14 30 -#define CAM_FORMAT_NV21 31 -#define CAM_FORMAT_NV12 32 -#define CAM_FORMAT_TP10 33 -#define CAM_FORMAT_YUV422 34 -#define CAM_FORMAT_PD8 35 -#define CAM_FORMAT_PD10 36 -#define CAM_FORMAT_UBWC_NV12 37 -#define CAM_FORMAT_UBWC_NV12_4R 38 -#define CAM_FORMAT_UBWC_TP10 39 -#define CAM_FORMAT_UBWC_P010 40 -#define CAM_FORMAT_PLAIN8_SWAP 41 -#define CAM_FORMAT_PLAIN8_10 42 -#define CAM_FORMAT_PLAIN8_10_SWAP 43 -#define CAM_FORMAT_YV12 44 -#define CAM_FORMAT_Y_ONLY 45 -#define CAM_FORMAT_MAX 46 - -/* camera rotaion */ -#define CAM_ROTATE_CW_0_DEGREE 0 -#define CAM_ROTATE_CW_90_DEGREE 1 -#define CAM_RORATE_CW_180_DEGREE 2 -#define CAM_ROTATE_CW_270_DEGREE 3 - -/* camera Color Space */ -#define CAM_COLOR_SPACE_BASE 0 -#define CAM_COLOR_SPACE_BT601_FULL 1 -#define CAM_COLOR_SPACE_BT601625 2 -#define CAM_COLOR_SPACE_BT601525 3 -#define CAM_COLOR_SPACE_BT709 4 -#define CAM_COLOR_SPACE_DEPTH 5 -#define CAM_COLOR_SPACE_MAX 6 - -/* camera buffer direction */ -#define CAM_BUF_INPUT 1 -#define CAM_BUF_OUTPUT 2 -#define CAM_BUF_IN_OUT 3 - -/* camera packet device Type */ -#define CAM_PACKET_DEV_BASE 0 -#define CAM_PACKET_DEV_IMG_SENSOR 1 -#define CAM_PACKET_DEV_ACTUATOR 2 -#define CAM_PACKET_DEV_COMPANION 3 -#define CAM_PACKET_DEV_EEPOM 4 -#define CAM_PACKET_DEV_CSIPHY 5 -#define CAM_PACKET_DEV_OIS 6 -#define CAM_PACKET_DEV_FLASH 7 -#define CAM_PACKET_DEV_FD 8 -#define CAM_PACKET_DEV_JPEG_ENC 9 -#define CAM_PACKET_DEV_JPEG_DEC 10 -#define CAM_PACKET_DEV_VFE 11 -#define CAM_PACKET_DEV_CPP 12 -#define CAM_PACKET_DEV_CSID 13 -#define CAM_PACKET_DEV_ISPIF 14 -#define CAM_PACKET_DEV_IFE 15 -#define CAM_PACKET_DEV_ICP 16 -#define CAM_PACKET_DEV_LRME 17 -#define CAM_PACKET_DEV_MAX 18 - - -/* constants */ -#define CAM_PACKET_MAX_PLANES 3 - -/** - * struct cam_plane_cfg - Plane configuration info - * - * @width: Plane width in pixels - * @height: Plane height in lines - * @plane_stride: Plane stride in pixel - * @slice_height: Slice height in line (not used by ISP) - * @meta_stride: UBWC metadata stride - * @meta_size: UBWC metadata plane size - * @meta_offset: UBWC metadata offset - * @packer_config: UBWC packer config - * @mode_config: UBWC mode config - * @tile_config: UBWC tile config - * @h_init: UBWC horizontal initial coordinate in pixels - * @v_init: UBWC vertical initial coordinate in lines - * - */ -struct cam_plane_cfg { - uint32_t width; - uint32_t height; - uint32_t plane_stride; - uint32_t slice_height; - uint32_t meta_stride; - uint32_t meta_size; - uint32_t meta_offset; - uint32_t packer_config; - uint32_t mode_config; - uint32_t tile_config; - uint32_t h_init; - uint32_t v_init; -}; - -/** - * struct cam_cmd_buf_desc - Command buffer descriptor - * - * @mem_handle: Command buffer handle - * @offset: Command start offset - * @size: Size of the command buffer in bytes - * @length: Used memory in command buffer in bytes - * @type: Type of the command buffer - * @meta_data: Data type for private command buffer - * Between UMD and KMD - * - */ -struct cam_cmd_buf_desc { - int32_t mem_handle; - uint32_t offset; - uint32_t size; - uint32_t length; - uint32_t type; - uint32_t meta_data; -}; - -/** - * struct cam_buf_io_cfg - Buffer io configuration for buffers - * - * @mem_handle: Mem_handle array for the buffers. - * @offsets: Offsets for each planes in the buffer - * @planes: Per plane information - * @width: Main plane width in pixel - * @height: Main plane height in lines - * @format: Format of the buffer - * @color_space: Color space for the buffer - * @color_pattern: Color pattern in the buffer - * @bpp: Bit per pixel - * @rotation: Rotation information for the buffer - * @resource_type: Resource type associated with the buffer - * @fence: Fence handle - * @early_fence: Fence handle for early signal - * @aux_cmd_buf: An auxiliary command buffer that may be - * used for programming the IO - * @direction: Direction of the config - * @batch_size: Batch size in HFR mode - * @subsample_pattern: Subsample pattern. Used in HFR mode. It - * should be consistent with batchSize and - * CAMIF programming. - * @subsample_period: Subsample period. Used in HFR mode. It - * should be consistent with batchSize and - * CAMIF programming. - * @framedrop_pattern: Framedrop pattern - * @framedrop_period: Framedrop period - * @flag: Flags for extra information - * @direction: Buffer direction: input or output - * @padding: Padding for the structure - * - */ -struct cam_buf_io_cfg { - int32_t mem_handle[CAM_PACKET_MAX_PLANES]; - uint32_t offsets[CAM_PACKET_MAX_PLANES]; - struct cam_plane_cfg planes[CAM_PACKET_MAX_PLANES]; - uint32_t format; - uint32_t color_space; - uint32_t color_pattern; - uint32_t bpp; - uint32_t rotation; - uint32_t resource_type; - int32_t fence; - int32_t early_fence; - struct cam_cmd_buf_desc aux_cmd_buf; - uint32_t direction; - uint32_t batch_size; - uint32_t subsample_pattern; - uint32_t subsample_period; - uint32_t framedrop_pattern; - uint32_t framedrop_period; - uint32_t flag; - uint32_t padding; -}; - -/** - * struct cam_packet_header - Camera packet header - * - * @op_code: Camera packet opcode - * @size: Size of the camera packet in bytes - * @request_id: Request id for this camera packet - * @flags: Flags for the camera packet - * @padding: Padding - * - */ -struct cam_packet_header { - uint32_t op_code; - uint32_t size; - uint64_t request_id; - uint32_t flags; - uint32_t padding; -}; - -/** - * struct cam_patch_desc - Patch structure - * - * @dst_buf_hdl: Memory handle for the dest buffer - * @dst_offset: Offset byte in the dest buffer - * @src_buf_hdl: Memory handle for the source buffer - * @src_offset: Offset byte in the source buffer - * - */ -struct cam_patch_desc { - int32_t dst_buf_hdl; - uint32_t dst_offset; - int32_t src_buf_hdl; - uint32_t src_offset; -}; - -/** - * struct cam_packet - Camera packet structure - * - * @header: Camera packet header - * @cmd_buf_offset: Command buffer start offset - * @num_cmd_buf: Number of the command buffer in the packet - * @io_config_offset: Buffer io configuration start offset - * @num_io_configs: Number of the buffer io configurations - * @patch_offset: Patch offset for the patch structure - * @num_patches: Number of the patch structure - * @kmd_cmd_buf_index: Command buffer index which contains extra - * space for the KMD buffer - * @kmd_cmd_buf_offset: Offset from the beginning of the command - * buffer for KMD usage. - * @payload: Camera packet payload - * - */ -struct cam_packet { - struct cam_packet_header header; - uint32_t cmd_buf_offset; - uint32_t num_cmd_buf; - uint32_t io_configs_offset; - uint32_t num_io_configs; - uint32_t patch_offset; - uint32_t num_patches; - uint32_t kmd_cmd_buf_index; - uint32_t kmd_cmd_buf_offset; - uint64_t payload[1]; - -}; - -/** - * struct cam_release_dev_cmd - Control payload for release devices - * - * @session_handle: Session handle for the release - * @dev_handle: Device handle for the release - */ -struct cam_release_dev_cmd { - int32_t session_handle; - int32_t dev_handle; -}; - -/** - * struct cam_start_stop_dev_cmd - Control payload for start/stop device - * - * @session_handle: Session handle for the start/stop command - * @dev_handle: Device handle for the start/stop command - * - */ -struct cam_start_stop_dev_cmd { - int32_t session_handle; - int32_t dev_handle; -}; - -/** - * struct cam_config_dev_cmd - Command payload for configure device - * - * @session_handle: Session handle for the command - * @dev_handle: Device handle for the command - * @offset: Offset byte in the packet handle. - * @packet_handle: Packet memory handle for the actual packet: - * struct cam_packet. - * - */ -struct cam_config_dev_cmd { - int32_t session_handle; - int32_t dev_handle; - uint64_t offset; - uint64_t packet_handle; -}; - -/** - * struct cam_query_cap_cmd - Payload for query device capability - * - * @size: Handle size - * @handle_type: User pointer or shared memory handle - * @caps_handle: Device specific query command payload - * - */ -struct cam_query_cap_cmd { - uint32_t size; - uint32_t handle_type; - uint64_t caps_handle; -}; - -/** - * struct cam_acquire_dev_cmd - Control payload for acquire devices - * - * @session_handle: Session handle for the acquire command - * @dev_handle: Device handle to be returned - * @handle_type: Resource handle type: - * 1 = user pointer, 2 = mem handle - * @num_resources: Number of the resources to be acquired - * @resources_hdl: Resource handle that refers to the actual - * resource array. Each item in this - * array is device specific resource structure - * - */ -struct cam_acquire_dev_cmd { - int32_t session_handle; - int32_t dev_handle; - uint32_t handle_type; - uint32_t num_resources; - uint64_t resource_hdl; -}; - -/** - * struct cam_flush_dev_cmd - Control payload for flush devices - * - * @version: Version - * @session_handle: Session handle for the acquire command - * @dev_handle: Device handle to be returned - * @flush_type: Flush type: - * 0 = flush specific request - * 1 = flush all - * @reserved: Reserved for 64 bit aligngment - * @req_id: Request id that needs to cancel - * - */ -struct cam_flush_dev_cmd { - uint64_t version; - int32_t session_handle; - int32_t dev_handle; - uint32_t flush_type; - uint32_t reserved; - int64_t req_id; -}; - -#endif /* __UAPI_CAM_DEFS_H__ */ diff --git a/third_party/linux/include/media/cam_fd.h b/third_party/linux/include/media/cam_fd.h deleted file mode 100644 index 8feb6e4da8..0000000000 --- a/third_party/linux/include/media/cam_fd.h +++ /dev/null @@ -1,127 +0,0 @@ -#ifndef __UAPI_CAM_FD_H__ -#define __UAPI_CAM_FD_H__ - -#include "cam_defs.h" - -#define CAM_FD_MAX_FACES 35 -#define CAM_FD_RAW_RESULT_ENTRIES 512 - -/* FD Op Codes */ -#define CAM_PACKET_OPCODES_FD_FRAME_UPDATE 0x0 - -/* FD Command Buffer identifiers */ -#define CAM_FD_CMD_BUFFER_ID_GENERIC 0x0 -#define CAM_FD_CMD_BUFFER_ID_CDM 0x1 -#define CAM_FD_CMD_BUFFER_ID_MAX 0x2 - -/* FD Blob types */ -#define CAM_FD_BLOB_TYPE_SOC_CLOCK_BW_REQUEST 0x0 -#define CAM_FD_BLOB_TYPE_RAW_RESULTS_REQUIRED 0x1 - -/* FD Resource IDs */ -#define CAM_FD_INPUT_PORT_ID_IMAGE 0x0 -#define CAM_FD_INPUT_PORT_ID_MAX 0x1 - -#define CAM_FD_OUTPUT_PORT_ID_RESULTS 0x0 -#define CAM_FD_OUTPUT_PORT_ID_RAW_RESULTS 0x1 -#define CAM_FD_OUTPUT_PORT_ID_WORK_BUFFER 0x2 -#define CAM_FD_OUTPUT_PORT_ID_MAX 0x3 - -/** - * struct cam_fd_soc_clock_bw_request - SOC clock, bandwidth request info - * - * @clock_rate : Clock rate required while processing frame - * @bandwidth : Bandwidth required while processing frame - * @reserved : Reserved for future use - */ -struct cam_fd_soc_clock_bw_request { - uint64_t clock_rate; - uint64_t bandwidth; - uint64_t reserved[4]; -}; - -/** - * struct cam_fd_face - Face properties - * - * @prop1 : Property 1 of face - * @prop2 : Property 2 of face - * @prop3 : Property 3 of face - * @prop4 : Property 4 of face - * - * Do not change this layout, this is inline with how HW writes - * these values directly when the buffer is programmed to HW - */ -struct cam_fd_face { - uint32_t prop1; - uint32_t prop2; - uint32_t prop3; - uint32_t prop4; -}; - -/** - * struct cam_fd_results - FD results layout - * - * @faces : Array of faces with face properties - * @face_count : Number of faces detected - * @reserved : Reserved for alignment - * - * Do not change this layout, this is inline with how HW writes - * these values directly when the buffer is programmed to HW - */ -struct cam_fd_results { - struct cam_fd_face faces[CAM_FD_MAX_FACES]; - uint32_t face_count; - uint32_t reserved[3]; -}; - -/** - * struct cam_fd_hw_caps - Face properties - * - * @core_version : FD core version - * @wrapper_version : FD wrapper version - * @raw_results_available : Whether raw results are available on this HW - * @supported_modes : Modes supported by this HW. - * @reserved : Reserved for future use - */ -struct cam_fd_hw_caps { - struct cam_hw_version core_version; - struct cam_hw_version wrapper_version; - uint32_t raw_results_available; - uint32_t supported_modes; - uint64_t reserved; -}; - -/** - * struct cam_fd_query_cap_cmd - FD Query capabilities information - * - * @device_iommu : FD IOMMU handles - * @cdm_iommu : CDM iommu handles - * @hw_caps : FD HW capabilities - * @reserved : Reserved for alignment - */ -struct cam_fd_query_cap_cmd { - struct cam_iommu_handle device_iommu; - struct cam_iommu_handle cdm_iommu; - struct cam_fd_hw_caps hw_caps; - uint64_t reserved; -}; - -/** - * struct cam_fd_acquire_dev_info - FD acquire device information - * - * @clk_bw_request : SOC clock, bandwidth request - * @priority : Priority for this acquire - * @mode : Mode in which to run FD HW. - * @get_raw_results : Whether this acquire needs face raw results - * while frame processing - * @reserved : Reserved field for 64 bit alignment - */ -struct cam_fd_acquire_dev_info { - struct cam_fd_soc_clock_bw_request clk_bw_request; - uint32_t priority; - uint32_t mode; - uint32_t get_raw_results; - uint32_t reserved[13]; -}; - -#endif /* __UAPI_CAM_FD_H__ */ diff --git a/third_party/linux/include/media/cam_icp.h b/third_party/linux/include/media/cam_icp.h deleted file mode 100644 index 680d05b630..0000000000 --- a/third_party/linux/include/media/cam_icp.h +++ /dev/null @@ -1,179 +0,0 @@ -#ifndef __UAPI_CAM_ICP_H__ -#define __UAPI_CAM_ICP_H__ - -#include "cam_defs.h" - -/* icp, ipe, bps, cdm(ipe/bps) are used in querycap */ -#define CAM_ICP_DEV_TYPE_A5 1 -#define CAM_ICP_DEV_TYPE_IPE 2 -#define CAM_ICP_DEV_TYPE_BPS 3 -#define CAM_ICP_DEV_TYPE_IPE_CDM 4 -#define CAM_ICP_DEV_TYPE_BPS_CDM 5 -#define CAM_ICP_DEV_TYPE_MAX 5 - -/* definitions needed for icp aquire device */ -#define CAM_ICP_RES_TYPE_BPS 1 -#define CAM_ICP_RES_TYPE_IPE_RT 2 -#define CAM_ICP_RES_TYPE_IPE 3 -#define CAM_ICP_RES_TYPE_MAX 4 - -/* packet opcode types */ -#define CAM_ICP_OPCODE_IPE_UPDATE 0 -#define CAM_ICP_OPCODE_BPS_UPDATE 1 - -/* IPE input port resource type */ -#define CAM_ICP_IPE_INPUT_IMAGE_FULL 0x0 -#define CAM_ICP_IPE_INPUT_IMAGE_DS4 0x1 -#define CAM_ICP_IPE_INPUT_IMAGE_DS16 0x2 -#define CAM_ICP_IPE_INPUT_IMAGE_DS64 0x3 -#define CAM_ICP_IPE_INPUT_IMAGE_FULL_REF 0x4 -#define CAM_ICP_IPE_INPUT_IMAGE_DS4_REF 0x5 -#define CAM_ICP_IPE_INPUT_IMAGE_DS16_REF 0x6 -#define CAM_ICP_IPE_INPUT_IMAGE_DS64_REF 0x7 - -/* IPE output port resource type */ -#define CAM_ICP_IPE_OUTPUT_IMAGE_DISPLAY 0x8 -#define CAM_ICP_IPE_OUTPUT_IMAGE_VIDEO 0x9 -#define CAM_ICP_IPE_OUTPUT_IMAGE_FULL_REF 0xA -#define CAM_ICP_IPE_OUTPUT_IMAGE_DS4_REF 0xB -#define CAM_ICP_IPE_OUTPUT_IMAGE_DS16_REF 0xC -#define CAM_ICP_IPE_OUTPUT_IMAGE_DS64_REF 0xD - -#define CAM_ICP_IPE_IMAGE_MAX 0xE - -/* BPS input port resource type */ -#define CAM_ICP_BPS_INPUT_IMAGE 0x0 - -/* BPS output port resource type */ -#define CAM_ICP_BPS_OUTPUT_IMAGE_FULL 0x1 -#define CAM_ICP_BPS_OUTPUT_IMAGE_DS4 0x2 -#define CAM_ICP_BPS_OUTPUT_IMAGE_DS16 0x3 -#define CAM_ICP_BPS_OUTPUT_IMAGE_DS64 0x4 -#define CAM_ICP_BPS_OUTPUT_IMAGE_STATS_BG 0x5 -#define CAM_ICP_BPS_OUTPUT_IMAGE_STATS_BHIST 0x6 -#define CAM_ICP_BPS_OUTPUT_IMAGE_REG1 0x7 -#define CAM_ICP_BPS_OUTPUT_IMAGE_REG2 0x8 - -#define CAM_ICP_BPS_IO_IMAGES_MAX 0x9 - -/* Command meta types */ -#define CAM_ICP_CMD_META_GENERIC_BLOB 0x1 - -/* Generic blob types */ -#define CAM_ICP_CMD_GENERIC_BLOB_CLK 0x1 -#define CAM_ICP_CMD_GENERIC_BLOB_CFG_IO 0x2 - -/** - * struct cam_icp_clk_bw_request - * - * @budget_ns: Time required to process frame - * @frame_cycles: Frame cycles needed to process the frame - * @rt_flag: Flag to indicate real time stream - * @uncompressed_bw: Bandwidth required to process frame - * @compressed_bw: Compressed bandwidth to process frame - */ -struct cam_icp_clk_bw_request { - uint64_t budget_ns; - uint32_t frame_cycles; - uint32_t rt_flag; - uint64_t uncompressed_bw; - uint64_t compressed_bw; -}; - -/** - * struct cam_icp_dev_ver - Device information for particular hw type - * - * This is used to get device version info of - * ICP, IPE, BPS and CDM related IPE and BPS from firmware - * and use this info in CAM_QUERY_CAP IOCTL - * - * @dev_type: hardware type for the cap info(icp, ipe, bps, cdm(ipe/bps)) - * @reserved: reserved field - * @hw_ver: major, minor and incr values of a device version - */ -struct cam_icp_dev_ver { - uint32_t dev_type; - uint32_t reserved; - struct cam_hw_version hw_ver; -}; - -/** - * struct cam_icp_ver - ICP version info - * - * This strcuture is used for fw and api version - * this is used to get firmware version and api version from firmware - * and use this info in CAM_QUERY_CAP IOCTL - * - * @major: FW version major - * @minor: FW version minor - * @revision: FW version increment - */ -struct cam_icp_ver { - uint32_t major; - uint32_t minor; - uint32_t revision; - uint32_t reserved; -}; - -/** - * struct cam_icp_query_cap_cmd - ICP query device capability payload - * - * @dev_iommu_handle: icp iommu handles for secure/non secure modes - * @cdm_iommu_handle: iommu handles for secure/non secure modes - * @fw_version: firmware version info - * @api_version: api version info - * @num_ipe: number of ipes - * @num_bps: number of bps - * @dev_ver: returned device capability array - */ -struct cam_icp_query_cap_cmd { - struct cam_iommu_handle dev_iommu_handle; - struct cam_iommu_handle cdm_iommu_handle; - struct cam_icp_ver fw_version; - struct cam_icp_ver api_version; - uint32_t num_ipe; - uint32_t num_bps; - struct cam_icp_dev_ver dev_ver[CAM_ICP_DEV_TYPE_MAX]; -}; - -/** - * struct cam_icp_res_info - ICP output resource info - * - * @format: format of the resource - * @width: width in pixels - * @height: height in lines - * @fps: fps - */ -struct cam_icp_res_info { - uint32_t format; - uint32_t width; - uint32_t height; - uint32_t fps; -}; - -/** - * struct cam_icp_acquire_dev_info - An ICP device info - * - * @scratch_mem_size: Output param - size of scratch memory - * @dev_type: device type (IPE_RT/IPE_NON_RT/BPS) - * @io_config_cmd_size: size of IO config command - * @io_config_cmd_handle: IO config command for each acquire - * @secure_mode: camera mode (secure/non secure) - * @chain_info: chaining info of FW device handles - * @in_res: resource info used for clock and bandwidth calculation - * @num_out_res: number of output resources - * @out_res: output resource - */ -struct cam_icp_acquire_dev_info { - uint32_t scratch_mem_size; - uint32_t dev_type; - uint32_t io_config_cmd_size; - int32_t io_config_cmd_handle; - uint32_t secure_mode; - int32_t chain_info; - struct cam_icp_res_info in_res; - uint32_t num_out_res; - struct cam_icp_res_info out_res[1]; -} __attribute__((__packed__)); - -#endif /* __UAPI_CAM_ICP_H__ */ diff --git a/third_party/linux/include/media/cam_isp.h b/third_party/linux/include/media/cam_isp.h deleted file mode 100644 index 266840d38c..0000000000 --- a/third_party/linux/include/media/cam_isp.h +++ /dev/null @@ -1,379 +0,0 @@ -#ifndef __UAPI_CAM_ISP_H__ -#define __UAPI_CAM_ISP_H__ - -#include "cam_defs.h" -#include "cam_isp_vfe.h" -#include "cam_isp_ife.h" - - -/* ISP driver name */ -#define CAM_ISP_DEV_NAME "cam-isp" - -/* HW type */ -#define CAM_ISP_HW_BASE 0 -#define CAM_ISP_HW_CSID 1 -#define CAM_ISP_HW_VFE 2 -#define CAM_ISP_HW_IFE 3 -#define CAM_ISP_HW_ISPIF 4 -#define CAM_ISP_HW_MAX 5 - -/* Color Pattern */ -#define CAM_ISP_PATTERN_BAYER_RGRGRG 0 -#define CAM_ISP_PATTERN_BAYER_GRGRGR 1 -#define CAM_ISP_PATTERN_BAYER_BGBGBG 2 -#define CAM_ISP_PATTERN_BAYER_GBGBGB 3 -#define CAM_ISP_PATTERN_YUV_YCBYCR 4 -#define CAM_ISP_PATTERN_YUV_YCRYCB 5 -#define CAM_ISP_PATTERN_YUV_CBYCRY 6 -#define CAM_ISP_PATTERN_YUV_CRYCBY 7 -#define CAM_ISP_PATTERN_MAX 8 - -/* Usage Type */ -#define CAM_ISP_RES_USAGE_SINGLE 0 -#define CAM_ISP_RES_USAGE_DUAL 1 -#define CAM_ISP_RES_USAGE_MAX 2 - -/* Resource ID */ -#define CAM_ISP_RES_ID_PORT 0 -#define CAM_ISP_RES_ID_CLK 1 -#define CAM_ISP_RES_ID_MAX 2 - -/* Resource Type - Type of resource for the resource id - * defined in cam_isp_vfe.h, cam_isp_ife.h - */ - -/* Lane Type in input resource for Port */ -#define CAM_ISP_LANE_TYPE_DPHY 0 -#define CAM_ISP_LANE_TYPE_CPHY 1 -#define CAM_ISP_LANE_TYPE_MAX 2 - -/* ISP Resurce Composite Group ID */ -#define CAM_ISP_RES_COMP_GROUP_NONE 0 -#define CAM_ISP_RES_COMP_GROUP_ID_0 1 -#define CAM_ISP_RES_COMP_GROUP_ID_1 2 -#define CAM_ISP_RES_COMP_GROUP_ID_2 3 -#define CAM_ISP_RES_COMP_GROUP_ID_3 4 -#define CAM_ISP_RES_COMP_GROUP_ID_4 5 -#define CAM_ISP_RES_COMP_GROUP_ID_5 6 -#define CAM_ISP_RES_COMP_GROUP_ID_MAX 6 - -/* ISP packet opcode for ISP */ -#define CAM_ISP_PACKET_OP_BASE 0 -#define CAM_ISP_PACKET_INIT_DEV 1 -#define CAM_ISP_PACKET_UPDATE_DEV 2 -#define CAM_ISP_PACKET_OP_MAX 3 - -/* ISP packet meta_data type for command buffer */ -#define CAM_ISP_PACKET_META_BASE 0 -#define CAM_ISP_PACKET_META_LEFT 1 -#define CAM_ISP_PACKET_META_RIGHT 2 -#define CAM_ISP_PACKET_META_COMMON 3 -#define CAM_ISP_PACKET_META_DMI_LEFT 4 -#define CAM_ISP_PACKET_META_DMI_RIGHT 5 -#define CAM_ISP_PACKET_META_DMI_COMMON 6 -#define CAM_ISP_PACKET_META_CLOCK 7 -#define CAM_ISP_PACKET_META_CSID 8 -#define CAM_ISP_PACKET_META_DUAL_CONFIG 9 -#define CAM_ISP_PACKET_META_GENERIC_BLOB_LEFT 10 -#define CAM_ISP_PACKET_META_GENERIC_BLOB_RIGHT 11 -#define CAM_ISP_PACKET_META_GENERIC_BLOB_COMMON 12 - -/* DSP mode */ -#define CAM_ISP_DSP_MODE_NONE 0 -#define CAM_ISP_DSP_MODE_ONE_WAY 1 -#define CAM_ISP_DSP_MODE_ROUND 2 - -/* ISP Generic Cmd Buffer Blob types */ -#define CAM_ISP_GENERIC_BLOB_TYPE_HFR_CONFIG 0 -#define CAM_ISP_GENERIC_BLOB_TYPE_CLOCK_CONFIG 1 -#define CAM_ISP_GENERIC_BLOB_TYPE_BW_CONFIG 2 - -/* Query devices */ -/** - * struct cam_isp_dev_cap_info - A cap info for particular hw type - * - * @hw_type: Hardware type for the cap info - * @reserved: reserved field for alignment - * @hw_version: Hardware version - * - */ -struct cam_isp_dev_cap_info { - uint32_t hw_type; - uint32_t reserved; - struct cam_hw_version hw_version; -}; - -/** - * struct cam_isp_query_cap_cmd - ISP query device capability payload - * - * @device_iommu: returned iommu handles for device - * @cdm_iommu: returned iommu handles for cdm - * @num_dev: returned number of device capabilities - * @reserved: reserved field for alignment - * @dev_caps: returned device capability array - * - */ -struct cam_isp_query_cap_cmd { - struct cam_iommu_handle device_iommu; - struct cam_iommu_handle cdm_iommu; - int32_t num_dev; - uint32_t reserved; - struct cam_isp_dev_cap_info dev_caps[CAM_ISP_HW_MAX]; -}; - -/* Acquire Device */ -/** - * struct cam_isp_out_port_info - An output port resource info - * - * @res_type: output resource type defined in file - * cam_isp_vfe.h or cam_isp_ife.h - * @format: output format of the resource - * @wdith: output width in pixels - * @height: output height in lines - * @comp_grp_id: composite group id for the resource. - * @split_point: split point in pixels for the dual VFE. - * @secure_mode: flag to tell if output should be run in secure - * mode or not. See cam_defs.h for definition - * @reserved: reserved field for alignment - * - */ -struct cam_isp_out_port_info { - uint32_t res_type; - uint32_t format; - uint32_t width; - uint32_t height; - uint32_t comp_grp_id; - uint32_t split_point; - uint32_t secure_mode; - uint32_t reserved; -}; - -/** - * struct cam_isp_in_port_info - An input port resource info - * - * @res_type: input resource type define in file - * cam_isp_vfe.h or cam_isp_ife.h - * @lane_type: lane type: c-phy or d-phy. - * @lane_num: active lane number - * @lane_cfg: lane configurations: 4 bits per lane - * @vc: input virtual channel number - * @dt: input data type number - * @format: input format - * @test_pattern: test pattern for the testgen - * @usage_type: whether dual vfe is required - * @left_start: left input start offset in pixels - * @left_stop: left input stop offset in pixels - * @left_width: left input width in pixels - * @right_start: right input start offset in pixels. - * Only for Dual VFE - * @right_stop: right input stop offset in pixels. - * Only for Dual VFE - * @right_width: right input width in pixels. - * Only for dual VFE - * @line_start: top of the line number - * @line_stop: bottome of the line number - * @height: input height in lines - * @pixel_clk; sensor output clock - * @batch_size: batch size for HFR mode - * @dsp_mode: DSP stream mode (Defines as CAM_ISP_DSP_MODE_*) - * @hbi_cnt: HBI count for the camif input - * @reserved: Reserved field for alignment - * @num_out_res: number of the output resource associated - * @data: payload that contains the output resources - * - */ -struct cam_isp_in_port_info { - uint32_t res_type; - uint32_t lane_type; - uint32_t lane_num; - uint32_t lane_cfg; - uint32_t vc; - uint32_t dt; - uint32_t format; - uint32_t test_pattern; - uint32_t usage_type; - uint32_t left_start; - uint32_t left_stop; - uint32_t left_width; - uint32_t right_start; - uint32_t right_stop; - uint32_t right_width; - uint32_t line_start; - uint32_t line_stop; - uint32_t height; - uint32_t pixel_clk; - uint32_t batch_size; - uint32_t dsp_mode; - uint32_t hbi_cnt; - uint32_t custom_csid; - uint32_t reserved; - uint32_t num_out_res; - struct cam_isp_out_port_info data[1]; -}; - -/** - * struct cam_isp_resource - A resource bundle - * - * @resoruce_id: resource id for the resource bundle - * @length: length of the while resource blob - * @handle_type: type of the resource handle - * @reserved: reserved field for alignment - * @res_hdl: resource handle that points to the - * resource array; - * - */ -struct cam_isp_resource { - uint32_t resource_id; - uint32_t length; - uint32_t handle_type; - uint32_t reserved; - uint64_t res_hdl; -}; - -/** - * struct cam_isp_port_hfr_config - HFR configuration for this port - * - * @resource_type: Resource type - * @subsample_pattern: Subsample pattern. Used in HFR mode. It - * should be consistent with batchSize and - * CAMIF programming. - * @subsample_period: Subsample period. Used in HFR mode. It - * should be consistent with batchSize and - * CAMIF programming. - * @framedrop_pattern: Framedrop pattern - * @framedrop_period: Framedrop period - * @reserved: Reserved for alignment - */ -struct cam_isp_port_hfr_config { - uint32_t resource_type; - uint32_t subsample_pattern; - uint32_t subsample_period; - uint32_t framedrop_pattern; - uint32_t framedrop_period; - uint32_t reserved; -} __attribute__((packed)); - -/** - * struct cam_isp_resource_hfr_config - Resource HFR configuration - * - * @num_ports: Number of ports - * @reserved: Reserved for alignment - * @port_hfr_config: HFR configuration for each IO port - */ -struct cam_isp_resource_hfr_config { - uint32_t num_ports; - uint32_t reserved; - struct cam_isp_port_hfr_config port_hfr_config[1]; -} __attribute__((packed)); - -/** - * struct cam_isp_dual_split_params - dual isp spilt parameters - * - * @split_point: Split point information x, where (0 < x < width) - * left ISP's input ends at x + righ padding and - * Right ISP's input starts at x - left padding - * @right_padding: Padding added past the split point for left - * ISP's input - * @left_padding: Padding added before split point for right - * ISP's input - * @reserved: Reserved filed for alignment - * - */ -struct cam_isp_dual_split_params { - uint32_t split_point; - uint32_t right_padding; - uint32_t left_padding; - uint32_t reserved; -}; - -/** - * struct cam_isp_dual_stripe_config - stripe config per bus client - * - * @offset: Start horizontal offset relative to - * output buffer - * In UBWC mode, this value indicates the H_INIT - * value in pixel - * @width: Width of the stripe in bytes - * @tileconfig Ubwc meta tile config. Contain the partial - * tile info - * @port_id: port id of ISP output - * - */ -struct cam_isp_dual_stripe_config { - uint32_t offset; - uint32_t width; - uint32_t tileconfig; - uint32_t port_id; -}; - -/** - * struct cam_isp_dual_config - dual isp configuration - * - * @num_ports Number of isp output ports - * @reserved Reserved field for alignment - * @split_params: Inpput split parameters - * @stripes: Stripe information - * - */ -struct cam_isp_dual_config { - uint32_t num_ports; - uint32_t reserved; - struct cam_isp_dual_split_params split_params; - struct cam_isp_dual_stripe_config stripes[1]; -} __attribute__((packed)); - -/** - * struct cam_isp_clock_config - Clock configuration - * - * @usage_type: Usage type (Single/Dual) - * @num_rdi: Number of RDI votes - * @left_pix_hz: Pixel Clock for Left ISP - * @right_pix_hz: Pixel Clock for Right ISP, valid only if Dual - * @rdi_hz: RDI Clock. ISP clock will be max of RDI and - * PIX clocks. For a particular context which ISP - * HW the RDI is allocated to is not known to UMD. - * Hence pass the clock and let KMD decide. - */ -struct cam_isp_clock_config { - uint32_t usage_type; - uint32_t num_rdi; - uint64_t left_pix_hz; - uint64_t right_pix_hz; - uint64_t rdi_hz[1]; -} __attribute__((packed)); - -/** - * struct cam_isp_bw_vote - Bandwidth vote information - * - * @resource_id: Resource ID - * @reserved: Reserved field for alignment - * @cam_bw_bps: Bandwidth vote for CAMNOC - * @ext_bw_bps: Bandwidth vote for path-to-DDR after CAMNOC - */ - -struct cam_isp_bw_vote { - uint32_t resource_id; - uint32_t reserved; - uint64_t cam_bw_bps; - uint64_t ext_bw_bps; -} __attribute__((packed)); - -/** - * struct cam_isp_bw_config - Bandwidth configuration - * - * @usage_type: Usage type (Single/Dual) - * @num_rdi: Number of RDI votes - * @left_pix_vote: Bandwidth vote for left ISP - * @right_pix_vote: Bandwidth vote for right ISP - * @rdi_vote: RDI bandwidth requirements - */ - -struct cam_isp_bw_config { - uint32_t usage_type; - uint32_t num_rdi; - struct cam_isp_bw_vote left_pix_vote; - struct cam_isp_bw_vote right_pix_vote; - struct cam_isp_bw_vote rdi_vote[1]; -} __attribute__((packed)); - -#endif /* __UAPI_CAM_ISP_H__ */ diff --git a/third_party/linux/include/media/cam_isp_ife.h b/third_party/linux/include/media/cam_isp_ife.h deleted file mode 100644 index f5e72813fc..0000000000 --- a/third_party/linux/include/media/cam_isp_ife.h +++ /dev/null @@ -1,39 +0,0 @@ -#ifndef __UAPI_CAM_ISP_IFE_H__ -#define __UAPI_CAM_ISP_IFE_H__ - -/* IFE output port resource type (global unique)*/ -#define CAM_ISP_IFE_OUT_RES_BASE 0x3000 - -#define CAM_ISP_IFE_OUT_RES_FULL (CAM_ISP_IFE_OUT_RES_BASE + 0) -#define CAM_ISP_IFE_OUT_RES_DS4 (CAM_ISP_IFE_OUT_RES_BASE + 1) -#define CAM_ISP_IFE_OUT_RES_DS16 (CAM_ISP_IFE_OUT_RES_BASE + 2) -#define CAM_ISP_IFE_OUT_RES_RAW_DUMP (CAM_ISP_IFE_OUT_RES_BASE + 3) -#define CAM_ISP_IFE_OUT_RES_FD (CAM_ISP_IFE_OUT_RES_BASE + 4) -#define CAM_ISP_IFE_OUT_RES_PDAF (CAM_ISP_IFE_OUT_RES_BASE + 5) -#define CAM_ISP_IFE_OUT_RES_RDI_0 (CAM_ISP_IFE_OUT_RES_BASE + 6) -#define CAM_ISP_IFE_OUT_RES_RDI_1 (CAM_ISP_IFE_OUT_RES_BASE + 7) -#define CAM_ISP_IFE_OUT_RES_RDI_2 (CAM_ISP_IFE_OUT_RES_BASE + 8) -#define CAM_ISP_IFE_OUT_RES_RDI_3 (CAM_ISP_IFE_OUT_RES_BASE + 9) -#define CAM_ISP_IFE_OUT_RES_STATS_HDR_BE (CAM_ISP_IFE_OUT_RES_BASE + 10) -#define CAM_ISP_IFE_OUT_RES_STATS_HDR_BHIST (CAM_ISP_IFE_OUT_RES_BASE + 11) -#define CAM_ISP_IFE_OUT_RES_STATS_TL_BG (CAM_ISP_IFE_OUT_RES_BASE + 12) -#define CAM_ISP_IFE_OUT_RES_STATS_BF (CAM_ISP_IFE_OUT_RES_BASE + 13) -#define CAM_ISP_IFE_OUT_RES_STATS_AWB_BG (CAM_ISP_IFE_OUT_RES_BASE + 14) -#define CAM_ISP_IFE_OUT_RES_STATS_BHIST (CAM_ISP_IFE_OUT_RES_BASE + 15) -#define CAM_ISP_IFE_OUT_RES_STATS_RS (CAM_ISP_IFE_OUT_RES_BASE + 16) -#define CAM_ISP_IFE_OUT_RES_STATS_CS (CAM_ISP_IFE_OUT_RES_BASE + 17) -#define CAM_ISP_IFE_OUT_RES_STATS_IHIST (CAM_ISP_IFE_OUT_RES_BASE + 18) -#define CAM_ISP_IFE_OUT_RES_MAX (CAM_ISP_IFE_OUT_RES_BASE + 19) - - -/* IFE input port resource type (global unique) */ -#define CAM_ISP_IFE_IN_RES_BASE 0x4000 - -#define CAM_ISP_IFE_IN_RES_TPG (CAM_ISP_IFE_IN_RES_BASE + 0) -#define CAM_ISP_IFE_IN_RES_PHY_0 (CAM_ISP_IFE_IN_RES_BASE + 1) -#define CAM_ISP_IFE_IN_RES_PHY_1 (CAM_ISP_IFE_IN_RES_BASE + 2) -#define CAM_ISP_IFE_IN_RES_PHY_2 (CAM_ISP_IFE_IN_RES_BASE + 3) -#define CAM_ISP_IFE_IN_RES_PHY_3 (CAM_ISP_IFE_IN_RES_BASE + 4) -#define CAM_ISP_IFE_IN_RES_MAX (CAM_ISP_IFE_IN_RES_BASE + 5) - -#endif /* __UAPI_CAM_ISP_IFE_H__ */ diff --git a/third_party/linux/include/media/cam_isp_vfe.h b/third_party/linux/include/media/cam_isp_vfe.h deleted file mode 100644 index e48db2f98d..0000000000 --- a/third_party/linux/include/media/cam_isp_vfe.h +++ /dev/null @@ -1,44 +0,0 @@ -#ifndef __UAPI_CAM_ISP_VFE_H__ -#define __UAPI_CAM_ISP_VFE_H__ - -/* VFE output port resource type (global unique) */ -#define CAM_ISP_VFE_OUT_RES_BASE 0x1000 - -#define CAM_ISP_VFE_OUT_RES_ENC (CAM_ISP_VFE_OUT_RES_BASE + 0) -#define CAM_ISP_VFE_OUT_RES_VIEW (CAM_ISP_VFE_OUT_RES_BASE + 1) -#define CAM_ISP_VFE_OUT_RES_VID (CAM_ISP_VFE_OUT_RES_BASE + 2) -#define CAM_ISP_VFE_OUT_RES_RDI_0 (CAM_ISP_VFE_OUT_RES_BASE + 3) -#define CAM_ISP_VFE_OUT_RES_RDI_1 (CAM_ISP_VFE_OUT_RES_BASE + 4) -#define CAM_ISP_VFE_OUT_RES_RDI_2 (CAM_ISP_VFE_OUT_RES_BASE + 5) -#define CAM_ISP_VFE_OUT_RES_RDI_3 (CAM_ISP_VFE_OUT_RES_BASE + 6) -#define CAM_ISP_VFE_OUT_RES_STATS_AEC (CAM_ISP_VFE_OUT_RES_BASE + 7) -#define CAM_ISP_VFE_OUT_RES_STATS_AF (CAM_ISP_VFE_OUT_RES_BASE + 8) -#define CAM_ISP_VFE_OUT_RES_STATS_AWB (CAM_ISP_VFE_OUT_RES_BASE + 9) -#define CAM_ISP_VFE_OUT_RES_STATS_RS (CAM_ISP_VFE_OUT_RES_BASE + 10) -#define CAM_ISP_VFE_OUT_RES_STATS_CS (CAM_ISP_VFE_OUT_RES_BASE + 11) -#define CAM_ISP_VFE_OUT_RES_STATS_IHIST (CAM_ISP_VFE_OUT_RES_BASE + 12) -#define CAM_ISP_VFE_OUT_RES_STATS_SKIN (CAM_ISP_VFE_OUT_RES_BASE + 13) -#define CAM_ISP_VFE_OUT_RES_STATS_BG (CAM_ISP_VFE_OUT_RES_BASE + 14) -#define CAM_ISP_VFE_OUT_RES_STATS_BF (CAM_ISP_VFE_OUT_RES_BASE + 15) -#define CAM_ISP_VFE_OUT_RES_STATS_BE (CAM_ISP_VFE_OUT_RES_BASE + 16) -#define CAM_ISP_VFE_OUT_RES_STATS_BHIST (CAM_ISP_VFE_OUT_RES_BASE + 17) -#define CAM_ISP_VFE_OUT_RES_STATS_BF_SCALE (CAM_ISP_VFE_OUT_RES_BASE + 18) -#define CAM_ISP_VFE_OUT_RES_STATS_HDR_BE (CAM_ISP_VFE_OUT_RES_BASE + 19) -#define CAM_ISP_VFE_OUT_RES_STATS_HDR_BHIST (CAM_ISP_VFE_OUT_RES_BASE + 20) -#define CAM_ISP_VFE_OUT_RES_STATS_AEC_BG (CAM_ISP_VFE_OUT_RES_BASE + 21) -#define CAM_ISP_VFE_OUT_RES_CAMIF_RAW (CAM_ISP_VFE_OUT_RES_BASE + 22) -#define CAM_ISP_VFE_OUT_RES_IDEAL_RAW (CAM_ISP_VFE_OUT_RES_BASE + 23) -#define CAM_ISP_VFE_OUT_RES_MAX (CAM_ISP_VFE_OUT_RES_BASE + 24) - -/* VFE input port_ resource type (global unique) */ -#define CAM_ISP_VFE_IN_RES_BASE 0x2000 - -#define CAM_ISP_VFE_IN_RES_TPG (CAM_ISP_VFE_IN_RES_BASE + 0) -#define CAM_ISP_VFE_IN_RES_PHY_0 (CAM_ISP_VFE_IN_RES_BASE + 1) -#define CAM_ISP_VFE_IN_RES_PHY_1 (CAM_ISP_VFE_IN_RES_BASE + 2) -#define CAM_ISP_VFE_IN_RES_PHY_2 (CAM_ISP_VFE_IN_RES_BASE + 3) -#define CAM_ISP_VFE_IN_RES_PHY_3 (CAM_ISP_VFE_IN_RES_BASE + 4) -#define CAM_ISP_VFE_IN_RES_FE (CAM_ISP_VFE_IN_RES_BASE + 5) -#define CAM_ISP_VFE_IN_RES_MAX (CAM_ISP_VFE_IN_RES_BASE + 6) - -#endif /* __UAPI_CAM_ISP_VFE_H__ */ diff --git a/third_party/linux/include/media/cam_jpeg.h b/third_party/linux/include/media/cam_jpeg.h deleted file mode 100644 index f3082f3bfe..0000000000 --- a/third_party/linux/include/media/cam_jpeg.h +++ /dev/null @@ -1,117 +0,0 @@ -#ifndef __UAPI_CAM_JPEG_H__ -#define __UAPI_CAM_JPEG_H__ - -#include "cam_defs.h" - -/* enc, dma, cdm(enc/dma) are used in querycap */ -#define CAM_JPEG_DEV_TYPE_ENC 0 -#define CAM_JPEG_DEV_TYPE_DMA 1 -#define CAM_JPEG_DEV_TYPE_MAX 2 - -#define CAM_JPEG_NUM_DEV_PER_RES_MAX 1 - -/* definitions needed for jpeg aquire device */ -#define CAM_JPEG_RES_TYPE_ENC 0 -#define CAM_JPEG_RES_TYPE_DMA 1 -#define CAM_JPEG_RES_TYPE_MAX 2 - -/* packet opcode types */ -#define CAM_JPEG_OPCODE_ENC_UPDATE 0 -#define CAM_JPEG_OPCODE_DMA_UPDATE 1 - -/* ENC input port resource type */ -#define CAM_JPEG_ENC_INPUT_IMAGE 0x0 - -/* ENC output port resource type */ -#define CAM_JPEG_ENC_OUTPUT_IMAGE 0x1 - -#define CAM_JPEG_ENC_IO_IMAGES_MAX 0x2 - -/* DMA input port resource type */ -#define CAM_JPEG_DMA_INPUT_IMAGE 0x0 - -/* DMA output port resource type */ -#define CAM_JPEG_DMA_OUTPUT_IMAGE 0x1 - -#define CAM_JPEG_DMA_IO_IMAGES_MAX 0x2 - -#define CAM_JPEG_IMAGE_MAX 0x2 - -/** - * struct cam_jpeg_dev_ver - Device information for particular hw type - * - * This is used to get device version info of JPEG ENC, JPEG DMA - * from hardware and use this info in CAM_QUERY_CAP IOCTL - * - * @size : Size of struct passed - * @dev_type: Hardware type for the cap info(jpeg enc, jpeg dma) - * @hw_ver: Major, minor and incr values of a device version - */ -struct cam_jpeg_dev_ver { - uint32_t size; - uint32_t dev_type; - struct cam_hw_version hw_ver; -}; - -/** - * struct cam_jpeg_query_cap_cmd - JPEG query device capability payload - * - * @dev_iommu_handle: Jpeg iommu handles for secure/non secure - * modes - * @cdm_iommu_handle: Iommu handles for secure/non secure modes - * @num_enc: Number of encoder - * @num_dma: Number of dma - * @dev_ver: Returned device capability array - */ -struct cam_jpeg_query_cap_cmd { - struct cam_iommu_handle dev_iommu_handle; - struct cam_iommu_handle cdm_iommu_handle; - uint32_t num_enc; - uint32_t num_dma; - struct cam_jpeg_dev_ver dev_ver[CAM_JPEG_DEV_TYPE_MAX]; -}; - -/** - * struct cam_jpeg_res_info - JPEG output resource info - * - * @format: Format of the resource - * @width: Width in pixels - * @height: Height in lines - * @fps: Fps - */ -struct cam_jpeg_res_info { - uint32_t format; - uint32_t width; - uint32_t height; - uint32_t fps; -}; - -/** - * struct cam_jpeg_acquire_dev_info - An JPEG device info - * - * @dev_type: Device type (ENC/DMA) - * @reserved: Reserved Bytes - * @in_res: In resource info - * @in_res: Iut resource info - */ -struct cam_jpeg_acquire_dev_info { - uint32_t dev_type; - uint32_t reserved; - struct cam_jpeg_res_info in_res; - struct cam_jpeg_res_info out_res; -}; - -/** - * struct cam_jpeg_config_inout_param_info - JPEG Config time - * input output params - * - * @clk_index: Input Param- clock selection index.(-1 default) - * @output_size: Output Param - jpeg encode/dma output size in - * bytes - */ -struct cam_jpeg_config_inout_param_info { - int32_t clk_index; - int32_t output_size; -}; - -#endif /* __UAPI_CAM_JPEG_H__ */ diff --git a/third_party/linux/include/media/cam_lrme.h b/third_party/linux/include/media/cam_lrme.h deleted file mode 100644 index 97d957835e..0000000000 --- a/third_party/linux/include/media/cam_lrme.h +++ /dev/null @@ -1,65 +0,0 @@ -#ifndef __UAPI_CAM_LRME_H__ -#define __UAPI_CAM_LRME_H__ - -#include "cam_defs.h" - -/* LRME Resource Types */ - -enum CAM_LRME_IO_TYPE { - CAM_LRME_IO_TYPE_TAR, - CAM_LRME_IO_TYPE_REF, - CAM_LRME_IO_TYPE_RES, - CAM_LRME_IO_TYPE_DS2, -}; - -#define CAM_LRME_INPUT_PORT_TYPE_TAR (1 << 0) -#define CAM_LRME_INPUT_PORT_TYPE_REF (1 << 1) - -#define CAM_LRME_OUTPUT_PORT_TYPE_DS2 (1 << 0) -#define CAM_LRME_OUTPUT_PORT_TYPE_RES (1 << 1) - -#define CAM_LRME_DEV_MAX 1 - - -struct cam_lrme_hw_version { - uint32_t gen; - uint32_t rev; - uint32_t step; -}; - -struct cam_lrme_dev_cap { - struct cam_lrme_hw_version clc_hw_version; - struct cam_lrme_hw_version bus_rd_hw_version; - struct cam_lrme_hw_version bus_wr_hw_version; - struct cam_lrme_hw_version top_hw_version; - struct cam_lrme_hw_version top_titan_version; -}; - -/** - * struct cam_lrme_query_cap_cmd - LRME query device capability payload - * - * @dev_iommu_handle: LRME iommu handles for secure/non secure - * modes - * @cdm_iommu_handle: Iommu handles for secure/non secure modes - * @num_devices: number of hardware devices - * @dev_caps: Returned device capability array - */ -struct cam_lrme_query_cap_cmd { - struct cam_iommu_handle device_iommu; - struct cam_iommu_handle cdm_iommu; - uint32_t num_devices; - struct cam_lrme_dev_cap dev_caps[CAM_LRME_DEV_MAX]; -}; - -struct cam_lrme_soc_info { - uint64_t clock_rate; - uint64_t bandwidth; - uint64_t reserved[4]; -}; - -struct cam_lrme_acquire_args { - struct cam_lrme_soc_info lrme_soc_info; -}; - -#endif /* __UAPI_CAM_LRME_H__ */ - diff --git a/third_party/linux/include/media/cam_req_mgr.h b/third_party/linux/include/media/cam_req_mgr.h deleted file mode 100644 index ae65649964..0000000000 --- a/third_party/linux/include/media/cam_req_mgr.h +++ /dev/null @@ -1,436 +0,0 @@ -#ifndef __UAPI_LINUX_CAM_REQ_MGR_H -#define __UAPI_LINUX_CAM_REQ_MGR_H - -#include -#include -#include -#include -#include - -#define CAM_REQ_MGR_VNODE_NAME "cam-req-mgr-devnode" - -#define CAM_DEVICE_TYPE_BASE (MEDIA_ENT_F_OLD_BASE) -#define CAM_VNODE_DEVICE_TYPE (CAM_DEVICE_TYPE_BASE) -#define CAM_SENSOR_DEVICE_TYPE (CAM_DEVICE_TYPE_BASE + 1) -#define CAM_IFE_DEVICE_TYPE (CAM_DEVICE_TYPE_BASE + 2) -#define CAM_ICP_DEVICE_TYPE (CAM_DEVICE_TYPE_BASE + 3) -#define CAM_LRME_DEVICE_TYPE (CAM_DEVICE_TYPE_BASE + 4) -#define CAM_JPEG_DEVICE_TYPE (CAM_DEVICE_TYPE_BASE + 5) -#define CAM_FD_DEVICE_TYPE (CAM_DEVICE_TYPE_BASE + 6) -#define CAM_CPAS_DEVICE_TYPE (CAM_DEVICE_TYPE_BASE + 7) -#define CAM_CSIPHY_DEVICE_TYPE (CAM_DEVICE_TYPE_BASE + 8) -#define CAM_ACTUATOR_DEVICE_TYPE (CAM_DEVICE_TYPE_BASE + 9) -#define CAM_CCI_DEVICE_TYPE (CAM_DEVICE_TYPE_BASE + 10) -#define CAM_FLASH_DEVICE_TYPE (CAM_DEVICE_TYPE_BASE + 11) -#define CAM_EEPROM_DEVICE_TYPE (CAM_DEVICE_TYPE_BASE + 12) -#define CAM_OIS_DEVICE_TYPE (CAM_DEVICE_TYPE_BASE + 13) - -/* cam_req_mgr hdl info */ -#define CAM_REQ_MGR_HDL_IDX_POS 8 -#define CAM_REQ_MGR_HDL_IDX_MASK ((1 << CAM_REQ_MGR_HDL_IDX_POS) - 1) -#define CAM_REQ_MGR_GET_HDL_IDX(hdl) (hdl & CAM_REQ_MGR_HDL_IDX_MASK) - -/** - * Max handles supported by cam_req_mgr - * It includes both session and device handles - */ -#define CAM_REQ_MGR_MAX_HANDLES 64 -#define MAX_LINKS_PER_SESSION 2 - -/* V4L event type which user space will subscribe to */ -#define V4L_EVENT_CAM_REQ_MGR_EVENT (V4L2_EVENT_PRIVATE_START + 0) - -/* Specific event ids to get notified in user space */ -#define V4L_EVENT_CAM_REQ_MGR_SOF 0 -#define V4L_EVENT_CAM_REQ_MGR_ERROR 1 -#define V4L_EVENT_CAM_REQ_MGR_SOF_BOOT_TS 2 - -/* SOF Event status */ -#define CAM_REQ_MGR_SOF_EVENT_SUCCESS 0 -#define CAM_REQ_MGR_SOF_EVENT_ERROR 1 - -/* Link control operations */ -#define CAM_REQ_MGR_LINK_ACTIVATE 0 -#define CAM_REQ_MGR_LINK_DEACTIVATE 1 - -/** - * Request Manager : flush_type - * @CAM_REQ_MGR_FLUSH_TYPE_ALL: Req mgr will remove all the pending - * requests from input/processing queue. - * @CAM_REQ_MGR_FLUSH_TYPE_CANCEL_REQ: Req mgr will remove only particular - * request id from input/processing queue. - * @CAM_REQ_MGR_FLUSH_TYPE_MAX: Max number of the flush type - * @opcode: CAM_REQ_MGR_FLUSH_REQ - */ -#define CAM_REQ_MGR_FLUSH_TYPE_ALL 0 -#define CAM_REQ_MGR_FLUSH_TYPE_CANCEL_REQ 1 -#define CAM_REQ_MGR_FLUSH_TYPE_MAX 2 - -/** - * Request Manager : Sync Mode type - * @CAM_REQ_MGR_SYNC_MODE_NO_SYNC: Req mgr will apply non-sync mode for this - * request. - * @CAM_REQ_MGR_SYNC_MODE_SYNC: Req mgr will apply sync mode for this request. - */ -#define CAM_REQ_MGR_SYNC_MODE_NO_SYNC 0 -#define CAM_REQ_MGR_SYNC_MODE_SYNC 1 - -/** - * struct cam_req_mgr_event_data - * @session_hdl: session handle - * @link_hdl: link handle - * @frame_id: frame id - * @reserved: reserved for 64 bit aligngment - * @req_id: request id - * @tv_sec: timestamp in seconds - * @tv_usec: timestamp in micro seconds - */ -struct cam_req_mgr_event_data { - int32_t session_hdl; - int32_t link_hdl; - int32_t frame_id; - int32_t reserved; - int64_t req_id; - uint64_t tv_sec; - uint64_t tv_usec; -}; - -/** - * struct cam_req_mgr_session_info - * @session_hdl: In/Output param - session_handle - * @opcode1: CAM_REQ_MGR_CREATE_SESSION - * @opcode2: CAM_REQ_MGR_DESTROY_SESSION - */ -struct cam_req_mgr_session_info { - int32_t session_hdl; - int32_t reserved; -}; - -/** - * struct cam_req_mgr_link_info - * @session_hdl: Input param - Identifier for CSL session - * @num_devices: Input Param - Num of devices to be linked - * @dev_hdls: Input param - List of device handles to be linked - * @link_hdl: Output Param -Identifier for link - * @opcode: CAM_REQ_MGR_LINK - */ -struct cam_req_mgr_link_info { - int32_t session_hdl; - uint32_t num_devices; - int32_t dev_hdls[CAM_REQ_MGR_MAX_HANDLES]; - int32_t link_hdl; -}; - -/** - * struct cam_req_mgr_unlink_info - * @session_hdl: input param - session handle - * @link_hdl: input param - link handle - * @opcode: CAM_REQ_MGR_UNLINK - */ -struct cam_req_mgr_unlink_info { - int32_t session_hdl; - int32_t link_hdl; -}; - -/** - * struct cam_req_mgr_flush_info - * @brief: User can tell drivers to flush a particular request id or - * flush all requests from its pending processing queue. Flush is a - * blocking call and driver shall ensure all requests are flushed - * before returning. - * @session_hdl: Input param - Identifier for CSL session - * @link_hdl: Input Param -Identifier for link - * @flush_type: User can cancel a particular req id or can flush - * all requests in queue - * @reserved: reserved for 64 bit aligngment - * @req_id: field is valid only if flush type is cancel request - * for flush all this field value is not considered. - * @opcode: CAM_REQ_MGR_FLUSH_REQ - */ -struct cam_req_mgr_flush_info { - int32_t session_hdl; - int32_t link_hdl; - uint32_t flush_type; - uint32_t reserved; - int64_t req_id; -}; - -/** struct cam_req_mgr_sched_info - * @session_hdl: Input param - Identifier for CSL session - * @link_hdl: Input Param -Identifier for link - * inluding itself. - * @bubble_enable: Input Param - Cam req mgr will do bubble recovery if this - * flag is set. - * @sync_mode: Type of Sync mode for this request - * @req_id: Input Param - Request Id from which all requests will be flushed - */ -struct cam_req_mgr_sched_request { - int32_t session_hdl; - int32_t link_hdl; - int32_t bubble_enable; - int32_t sync_mode; - int64_t req_id; -}; - -/** - * struct cam_req_mgr_sync_mode - * @session_hdl: Input param - Identifier for CSL session - * @sync_mode: Input Param - Type of sync mode - * @num_links: Input Param - Num of links in sync mode (Valid only - * when sync_mode is one of SYNC enabled modes) - * @link_hdls: Input Param - Array of link handles to be in sync mode - * (Valid only when sync_mode is one of SYNC - * enabled modes) - * @master_link_hdl: Input Param - To dictate which link's SOF drives system - * (Valid only when sync_mode is one of SYNC - * enabled modes) - * - * @opcode: CAM_REQ_MGR_SYNC_MODE - */ -struct cam_req_mgr_sync_mode { - int32_t session_hdl; - int32_t sync_mode; - int32_t num_links; - int32_t link_hdls[MAX_LINKS_PER_SESSION]; - int32_t master_link_hdl; - int32_t reserved; -}; - -/** - * struct cam_req_mgr_link_control - * @ops: Link operations: activate/deactive - * @session_hdl: Input param - Identifier for CSL session - * @num_links: Input Param - Num of links - * @reserved: reserved field - * @link_hdls: Input Param - Links to be activated/deactivated - * - * @opcode: CAM_REQ_MGR_LINK_CONTROL - */ -struct cam_req_mgr_link_control { - int32_t ops; - int32_t session_hdl; - int32_t num_links; - int32_t reserved; - int32_t link_hdls[MAX_LINKS_PER_SESSION]; -}; - -/** - * cam_req_mgr specific opcode ids - */ -#define CAM_REQ_MGR_CREATE_DEV_NODES (CAM_COMMON_OPCODE_MAX + 1) -#define CAM_REQ_MGR_CREATE_SESSION (CAM_COMMON_OPCODE_MAX + 2) -#define CAM_REQ_MGR_DESTROY_SESSION (CAM_COMMON_OPCODE_MAX + 3) -#define CAM_REQ_MGR_LINK (CAM_COMMON_OPCODE_MAX + 4) -#define CAM_REQ_MGR_UNLINK (CAM_COMMON_OPCODE_MAX + 5) -#define CAM_REQ_MGR_SCHED_REQ (CAM_COMMON_OPCODE_MAX + 6) -#define CAM_REQ_MGR_FLUSH_REQ (CAM_COMMON_OPCODE_MAX + 7) -#define CAM_REQ_MGR_SYNC_MODE (CAM_COMMON_OPCODE_MAX + 8) -#define CAM_REQ_MGR_ALLOC_BUF (CAM_COMMON_OPCODE_MAX + 9) -#define CAM_REQ_MGR_MAP_BUF (CAM_COMMON_OPCODE_MAX + 10) -#define CAM_REQ_MGR_RELEASE_BUF (CAM_COMMON_OPCODE_MAX + 11) -#define CAM_REQ_MGR_CACHE_OPS (CAM_COMMON_OPCODE_MAX + 12) -#define CAM_REQ_MGR_LINK_CONTROL (CAM_COMMON_OPCODE_MAX + 13) -/* end of cam_req_mgr opcodes */ - -#define CAM_MEM_FLAG_HW_READ_WRITE (1<<0) -#define CAM_MEM_FLAG_HW_READ_ONLY (1<<1) -#define CAM_MEM_FLAG_HW_WRITE_ONLY (1<<2) -#define CAM_MEM_FLAG_KMD_ACCESS (1<<3) -#define CAM_MEM_FLAG_UMD_ACCESS (1<<4) -#define CAM_MEM_FLAG_PROTECTED_MODE (1<<5) -#define CAM_MEM_FLAG_CMD_BUF_TYPE (1<<6) -#define CAM_MEM_FLAG_PIXEL_BUF_TYPE (1<<7) -#define CAM_MEM_FLAG_STATS_BUF_TYPE (1<<8) -#define CAM_MEM_FLAG_PACKET_BUF_TYPE (1<<9) -#define CAM_MEM_FLAG_CACHE (1<<10) -#define CAM_MEM_FLAG_HW_SHARED_ACCESS (1<<11) - -#define CAM_MEM_MMU_MAX_HANDLE 16 - -/* Maximum allowed buffers in existence */ -#define CAM_MEM_BUFQ_MAX 1024 - -#define CAM_MEM_MGR_SECURE_BIT_POS 15 -#define CAM_MEM_MGR_HDL_IDX_SIZE 15 -#define CAM_MEM_MGR_HDL_FD_SIZE 16 -#define CAM_MEM_MGR_HDL_IDX_END_POS 16 -#define CAM_MEM_MGR_HDL_FD_END_POS 32 - -#define CAM_MEM_MGR_HDL_IDX_MASK ((1 << CAM_MEM_MGR_HDL_IDX_SIZE) - 1) - -#define GET_MEM_HANDLE(idx, fd) \ - ((idx & CAM_MEM_MGR_HDL_IDX_MASK) | \ - (fd << (CAM_MEM_MGR_HDL_FD_END_POS - CAM_MEM_MGR_HDL_FD_SIZE))) \ - -#define GET_FD_FROM_HANDLE(hdl) \ - (hdl >> (CAM_MEM_MGR_HDL_FD_END_POS - CAM_MEM_MGR_HDL_FD_SIZE)) \ - -#define CAM_MEM_MGR_GET_HDL_IDX(hdl) (hdl & CAM_MEM_MGR_HDL_IDX_MASK) - -#define CAM_MEM_MGR_SET_SECURE_HDL(hdl, flag) \ - ((flag) ? (hdl |= (1 << CAM_MEM_MGR_SECURE_BIT_POS)) : \ - ((hdl) &= ~(1 << CAM_MEM_MGR_SECURE_BIT_POS))) - -#define CAM_MEM_MGR_IS_SECURE_HDL(hdl) \ - (((hdl) & \ - (1<> CAM_MEM_MGR_SECURE_BIT_POS) - -/** - * memory allocation type - */ -#define CAM_MEM_DMA_NONE 0 -#define CAM_MEM_DMA_BIDIRECTIONAL 1 -#define CAM_MEM_DMA_TO_DEVICE 2 -#define CAM_MEM_DMA_FROM_DEVICE 3 - - -/** - * memory cache operation - */ -#define CAM_MEM_CLEAN_CACHE 1 -#define CAM_MEM_INV_CACHE 2 -#define CAM_MEM_CLEAN_INV_CACHE 3 - - -/** - * struct cam_mem_alloc_out_params - * @buf_handle: buffer handle - * @fd: output buffer file descriptor - * @vaddr: virtual address pointer - */ -struct cam_mem_alloc_out_params { - uint32_t buf_handle; - int32_t fd; - uint64_t vaddr; -}; - -/** - * struct cam_mem_map_out_params - * @buf_handle: buffer handle - * @reserved: reserved for future - * @vaddr: virtual address pointer - */ -struct cam_mem_map_out_params { - uint32_t buf_handle; - uint32_t reserved; - uint64_t vaddr; -}; - -/** - * struct cam_mem_mgr_alloc_cmd - * @len: size of buffer to allocate - * @align: alignment of the buffer - * @mmu_hdls: array of mmu handles - * @num_hdl: number of handles - * @flags: flags of the buffer - * @out: out params - */ -/* CAM_REQ_MGR_ALLOC_BUF */ -struct cam_mem_mgr_alloc_cmd { - uint64_t len; - uint64_t align; - int32_t mmu_hdls[CAM_MEM_MMU_MAX_HANDLE]; - uint32_t num_hdl; - uint32_t flags; - struct cam_mem_alloc_out_params out; -}; - -/** - * struct cam_mem_mgr_map_cmd - * @mmu_hdls: array of mmu handles - * @num_hdl: number of handles - * @flags: flags of the buffer - * @fd: output buffer file descriptor - * @reserved: reserved field - * @out: out params - */ - -/* CAM_REQ_MGR_MAP_BUF */ -struct cam_mem_mgr_map_cmd { - int32_t mmu_hdls[CAM_MEM_MMU_MAX_HANDLE]; - uint32_t num_hdl; - uint32_t flags; - int32_t fd; - uint32_t reserved; - struct cam_mem_map_out_params out; -}; - -/** - * struct cam_mem_mgr_map_cmd - * @buf_handle: buffer handle - * @reserved: reserved field - */ -/* CAM_REQ_MGR_RELEASE_BUF */ -struct cam_mem_mgr_release_cmd { - int32_t buf_handle; - uint32_t reserved; -}; - -/** - * struct cam_mem_mgr_map_cmd - * @buf_handle: buffer handle - * @ops: cache operations - */ -/* CAM_REQ_MGR_CACHE_OPS */ -struct cam_mem_cache_ops_cmd { - int32_t buf_handle; - uint32_t mem_cache_ops; -}; - -/** - * Request Manager : error message type - * @CAM_REQ_MGR_ERROR_TYPE_DEVICE: Device error message, fatal to session - * @CAM_REQ_MGR_ERROR_TYPE_REQUEST: Error on a single request, not fatal - * @CAM_REQ_MGR_ERROR_TYPE_BUFFER: Buffer was not filled, not fatal - */ -#define CAM_REQ_MGR_ERROR_TYPE_DEVICE 0 -#define CAM_REQ_MGR_ERROR_TYPE_REQUEST 1 -#define CAM_REQ_MGR_ERROR_TYPE_BUFFER 2 - -/** - * struct cam_req_mgr_error_msg - * @error_type: type of error - * @request_id: request id of frame - * @device_hdl: device handle - * @linke_hdl: link_hdl - * @resource_size: size of the resource - */ -struct cam_req_mgr_error_msg { - uint32_t error_type; - uint32_t request_id; - int32_t device_hdl; - int32_t link_hdl; - uint64_t resource_size; -}; - -/** - * struct cam_req_mgr_frame_msg - * @request_id: request id of the frame - * @frame_id: frame id of the frame - * @timestamp: timestamp of the frame - * @link_hdl: link handle associated with this message - * @sof_status: sof status success or fail - */ -struct cam_req_mgr_frame_msg { - uint64_t request_id; - uint64_t frame_id; - uint64_t timestamp; - int32_t link_hdl; - uint32_t sof_status; -}; - -/** - * struct cam_req_mgr_message - * @session_hdl: session to which the frame belongs to - * @reserved: reserved field - * @u: union which can either be error or frame message - */ -struct cam_req_mgr_message { - int32_t session_hdl; - int32_t reserved; - union { - struct cam_req_mgr_error_msg err_msg; - struct cam_req_mgr_frame_msg frame_msg; - } u; -}; -#endif /* __UAPI_LINUX_CAM_REQ_MGR_H */ diff --git a/third_party/linux/include/media/cam_sensor.h b/third_party/linux/include/media/cam_sensor.h deleted file mode 100644 index f5af6047f5..0000000000 --- a/third_party/linux/include/media/cam_sensor.h +++ /dev/null @@ -1,477 +0,0 @@ -#ifndef __UAPI_CAM_SENSOR_H__ -#define __UAPI_CAM_SENSOR_H__ - -#include -#include -#include - -#define CAM_SENSOR_PROBE_CMD (CAM_COMMON_OPCODE_MAX + 1) -#define CAM_FLASH_MAX_LED_TRIGGERS 3 -#define MAX_OIS_NAME_SIZE 32 -#define CAM_CSIPHY_SECURE_MODE_ENABLED 1 -/** - * struct cam_sensor_query_cap - capabilities info for sensor - * - * @slot_info : Indicates about the slotId or cell Index - * @secure_camera : Camera is in secure/Non-secure mode - * @pos_pitch : Sensor position pitch - * @pos_roll : Sensor position roll - * @pos_yaw : Sensor position yaw - * @actuator_slot_id : Actuator slot id which connected to sensor - * @eeprom_slot_id : EEPROM slot id which connected to sensor - * @ois_slot_id : OIS slot id which connected to sensor - * @flash_slot_id : Flash slot id which connected to sensor - * @csiphy_slot_id : CSIphy slot id which connected to sensor - * - */ -struct cam_sensor_query_cap { - uint32_t slot_info; - uint32_t secure_camera; - uint32_t pos_pitch; - uint32_t pos_roll; - uint32_t pos_yaw; - uint32_t actuator_slot_id; - uint32_t eeprom_slot_id; - uint32_t ois_slot_id; - uint32_t flash_slot_id; - uint32_t csiphy_slot_id; -} __attribute__((packed)); - -/** - * struct cam_csiphy_query_cap - capabilities info for csiphy - * - * @slot_info : Indicates about the slotId or cell Index - * @version : CSIphy version - * @clk lane : Of the 5 lanes, informs lane configured - * as clock lane - * @reserved - */ -struct cam_csiphy_query_cap { - uint32_t slot_info; - uint32_t version; - uint32_t clk_lane; - uint32_t reserved; -} __attribute__((packed)); - -/** - * struct cam_actuator_query_cap - capabilities info for actuator - * - * @slot_info : Indicates about the slotId or cell Index - * @reserved - */ -struct cam_actuator_query_cap { - uint32_t slot_info; - uint32_t reserved; -} __attribute__((packed)); - -/** - * struct cam_eeprom_query_cap_t - capabilities info for eeprom - * - * @slot_info : Indicates about the slotId or cell Index - * @eeprom_kernel_probe : Indicates about the kernel or userspace probe - */ -struct cam_eeprom_query_cap_t { - uint32_t slot_info; - uint16_t eeprom_kernel_probe; - uint16_t reserved; -} __attribute__((packed)); - -/** - * struct cam_ois_query_cap_t - capabilities info for ois - * - * @slot_info : Indicates about the slotId or cell Index - */ -struct cam_ois_query_cap_t { - uint32_t slot_info; - uint16_t reserved; -} __attribute__((packed)); - -/** - * struct cam_cmd_i2c_info - Contains slave I2C related info - * - * @slave_addr : Slave address - * @i2c_freq_mode : 4 bits are used for I2c freq mode - * @cmd_type : Explains type of command - */ -struct cam_cmd_i2c_info { - uint16_t slave_addr; - uint8_t i2c_freq_mode; - uint8_t cmd_type; -} __attribute__((packed)); - -/** - * struct cam_ois_opcode - Contains OIS opcode - * - * @prog : OIS FW prog register address - * @coeff : OIS FW coeff register address - * @pheripheral : OIS pheripheral - * @memory : OIS memory - */ -struct cam_ois_opcode { - uint32_t prog; - uint32_t coeff; - uint32_t pheripheral; - uint32_t memory; -} __attribute__((packed)); - -/** - * struct cam_cmd_ois_info - Contains OIS slave info - * - * @slave_addr : OIS i2c slave address - * @i2c_freq_mode : i2c frequency mode - * @cmd_type : Explains type of command - * @ois_fw_flag : indicates if fw is present or not - * @is_ois_calib : indicates the calibration data is available - * @ois_name : OIS name - * @opcode : opcode - */ -struct cam_cmd_ois_info { - uint16_t slave_addr; - uint8_t i2c_freq_mode; - uint8_t cmd_type; - uint8_t ois_fw_flag; - uint8_t is_ois_calib; - char ois_name[MAX_OIS_NAME_SIZE]; - struct cam_ois_opcode opcode; -} __attribute__((packed)); - -/** - * struct cam_cmd_probe - Contains sensor slave info - * - * @data_type : Slave register data type - * @addr_type : Slave register address type - * @op_code : Don't Care - * @cmd_type : Explains type of command - * @reg_addr : Slave register address - * @expected_data : Data expected at slave register address - * @data_mask : Data mask if only few bits are valid - * @camera_id : Indicates the slot to which camera - * needs to be probed - * @reserved - */ -struct cam_cmd_probe { - uint8_t data_type; - uint8_t addr_type; - uint8_t op_code; - uint8_t cmd_type; - uint32_t reg_addr; - uint32_t expected_data; - uint32_t data_mask; - uint16_t camera_id; - uint16_t reserved; -} __attribute__((packed)); - -/** - * struct cam_power_settings - Contains sensor power setting info - * - * @power_seq_type : Type of power sequence - * @reserved - * @config_val_low : Lower 32 bit value configuration value - * @config_val_high : Higher 32 bit value configuration value - * - */ -struct cam_power_settings { - uint16_t power_seq_type; - uint16_t reserved; - uint32_t config_val_low; - uint32_t config_val_high; -} __attribute__((packed)); - -/** - * struct cam_cmd_power - Explains about the power settings - * - * @count : Number of power settings follows - * @reserved - * @cmd_type : Explains type of command - * @power_settings : Contains power setting info - */ -struct cam_cmd_power { - uint16_t count; - uint8_t reserved; - uint8_t cmd_type; - struct cam_power_settings power_settings[1]; -} __attribute__((packed)); - -/** - * struct i2c_rdwr_header - header of READ/WRITE I2C command - * - * @ count : Number of registers / data / reg-data pairs - * @ op_code : Operation code - * @ cmd_type : Command buffer type - * @ data_type : I2C data type - * @ addr_type : I2C address type - * @ reserved - */ -struct i2c_rdwr_header { - uint16_t count; - uint8_t op_code; - uint8_t cmd_type; - uint8_t data_type; - uint8_t addr_type; - uint16_t reserved; -} __attribute__((packed)); - -/** - * struct i2c_random_wr_payload - payload for I2C random write - * - * @ reg_addr : Register address - * @ reg_data : Register data - * - */ -struct i2c_random_wr_payload { - uint32_t reg_addr; - uint32_t reg_data; -} __attribute__((packed)); - -/** - * struct cam_cmd_i2c_random_wr - I2C random write command - * @ header : header of READ/WRITE I2C command - * @ random_wr_payload : payload for I2C random write - */ -struct cam_cmd_i2c_random_wr { - struct i2c_rdwr_header header; - struct i2c_random_wr_payload random_wr_payload[1]; -} __attribute__((packed)); - -/** - * struct cam_cmd_read - I2C read command - * @ reg_data : Register data - * @ reserved - */ -struct cam_cmd_read { - uint32_t reg_data; - uint32_t reserved; -} __attribute__((packed)); - -/** - * struct cam_cmd_i2c_continuous_wr - I2C continuous write command - * @ header : header of READ/WRITE I2C command - * @ reg_addr : Register address - * @ data_read : I2C read command - */ -struct cam_cmd_i2c_continuous_wr { - struct i2c_rdwr_header header; - uint32_t reg_addr; - struct cam_cmd_read data_read[1]; -} __attribute__((packed)); - -/** - * struct cam_cmd_i2c_random_rd - I2C random read command - * @ header : header of READ/WRITE I2C command - * @ data_read : I2C read command - */ -struct cam_cmd_i2c_random_rd { - struct i2c_rdwr_header header; - struct cam_cmd_read data_read[1]; -} __attribute__((packed)); - -/** - * struct cam_cmd_i2c_continuous_rd - I2C continuous continuous read command - * @ header : header of READ/WRITE I2C command - * @ reg_addr : Register address - * - */ -struct cam_cmd_i2c_continuous_rd { - struct i2c_rdwr_header header; - uint32_t reg_addr; -} __attribute__((packed)); - -/** - * struct cam_cmd_conditional_wait - Conditional wait command - * @data_type : Data type - * @addr_type : Address type - * @op_code : Opcode - * @cmd_type : Explains type of command - * @timeout : Timeout for retries - * @reserved - * @reg_addr : Register Address - * @reg_data : Register data - * @data_mask : Data mask if only few bits are valid - * @camera_id : Indicates the slot to which camera - * needs to be probed - * - */ -struct cam_cmd_conditional_wait { - uint8_t data_type; - uint8_t addr_type; - uint8_t op_code; - uint8_t cmd_type; - uint16_t timeout; - uint16_t reserved; - uint32_t reg_addr; - uint32_t reg_data; - uint32_t data_mask; -} __attribute__((packed)); - -/** - * struct cam_cmd_unconditional_wait - Un-conditional wait command - * @delay : Delay - * @op_code : Opcode - * @cmd_type : Explains type of command - */ -struct cam_cmd_unconditional_wait { - int16_t delay; - uint8_t op_code; - uint8_t cmd_type; -} __attribute__((packed)); - -/** - * cam_csiphy_info: Provides cmdbuffer structre - * @lane_mask : Lane mask details - * @lane_assign : Lane sensor will be using - * @csiphy_3phase : Total number of lanes - * @combo_mode : Info regarding combo_mode is enable / disable - * @lane_cnt : Total number of lanes - * @secure_mode : Secure mode flag to enable / disable - * @3phase : Details whether 3Phase / 2Phase operation - * @settle_time : Settling time in ms - * @data_rate : Data rate - * - */ -struct cam_csiphy_info { - uint16_t lane_mask; - uint16_t lane_assign; - uint8_t csiphy_3phase; - uint8_t combo_mode; - uint8_t lane_cnt; - uint8_t secure_mode; - uint64_t settle_time; - uint64_t data_rate; -} __attribute__((packed)); - -/** - * cam_csiphy_acquire_dev_info : Information needed for - * csiphy at the time of acquire - * @combo_mode : Indicates the device mode of operation - * @reserved - * - */ -struct cam_csiphy_acquire_dev_info { - uint32_t combo_mode; - uint32_t reserved; -} __attribute__((packed)); - -/** - * cam_sensor_acquire_dev : Updates sensor acuire cmd - * @device_handle : Updates device handle - * @session_handle : Session handle for acquiring device - * @handle_type : Resource handle type - * @reserved - * @info_handle : Handle to additional info - * needed for sensor sub modules - * - */ -struct cam_sensor_acquire_dev { - uint32_t session_handle; - uint32_t device_handle; - uint32_t handle_type; - uint32_t reserved; - uint64_t info_handle; -} __attribute__((packed)); - -/** - * cam_sensor_streamon_dev : StreamOn command for the sensor - * @session_handle : Session handle for acquiring device - * @device_handle : Updates device handle - * @handle_type : Resource handle type - * @reserved - * @info_handle : Information Needed at the time of streamOn - * - */ -struct cam_sensor_streamon_dev { - uint32_t session_handle; - uint32_t device_handle; - uint32_t handle_type; - uint32_t reserved; - uint64_t info_handle; -} __attribute__((packed)); - -/** - * struct cam_flash_init : Init command for the flash - * @flash_type : flash hw type - * @reserved - * @cmd_type : command buffer type - */ -struct cam_flash_init { - uint8_t flash_type; - uint16_t reserved; - uint8_t cmd_type; -} __attribute__((packed)); - -/** - * struct cam_flash_set_rer : RedEyeReduction command buffer - * - * @count : Number of flash leds - * @opcode : Command buffer opcode - * CAM_FLASH_FIRE_RER - * @cmd_type : command buffer operation type - * @num_iteration : Number of led turn on/off sequence - * @reserved - * @led_on_delay_ms : flash led turn on time in ms - * @led_off_delay_ms : flash led turn off time in ms - * @led_current_ma : flash led current in ma - * - */ -struct cam_flash_set_rer { - uint16_t count; - uint8_t opcode; - uint8_t cmd_type; - uint16_t num_iteration; - uint16_t reserved; - uint32_t led_on_delay_ms; - uint32_t led_off_delay_ms; - uint32_t led_current_ma[CAM_FLASH_MAX_LED_TRIGGERS]; -} __attribute__((packed)); - -/** - * struct cam_flash_set_on_off : led turn on/off command buffer - * - * @count : Number of Flash leds - * @opcode : command buffer opcodes - * CAM_FLASH_FIRE_LOW - * CAM_FLASH_FIRE_HIGH - * CAM_FLASH_OFF - * @cmd_type : command buffer operation type - * @led_current_ma : flash led current in ma - * - */ -struct cam_flash_set_on_off { - uint16_t count; - uint8_t opcode; - uint8_t cmd_type; - uint32_t led_current_ma[CAM_FLASH_MAX_LED_TRIGGERS]; -} __attribute__((packed)); - -/** - * struct cam_flash_query_curr : query current command buffer - * - * @reserved - * @opcode : command buffer opcode - * @cmd_type : command buffer operation type - * @query_current_ma : battery current in ma - * - */ -struct cam_flash_query_curr { - uint16_t reserved; - uint8_t opcode; - uint8_t cmd_type; - uint32_t query_current_ma; -} __attribute__ ((packed)); - -/** - * struct cam_flash_query_cap : capabilities info for flash - * - * @slot_info : Indicates about the slotId or cell Index - * @max_current_flash : max supported current for flash - * @max_duration_flash : max flash turn on duration - * @max_current_torch : max supported current for torch - * - */ -struct cam_flash_query_cap_info { - uint32_t slot_info; - uint32_t max_current_flash[CAM_FLASH_MAX_LED_TRIGGERS]; - uint32_t max_duration_flash[CAM_FLASH_MAX_LED_TRIGGERS]; - uint32_t max_current_torch[CAM_FLASH_MAX_LED_TRIGGERS]; -} __attribute__ ((packed)); - -#endif diff --git a/third_party/linux/include/media/cam_sensor_cmn_header.h b/third_party/linux/include/media/cam_sensor_cmn_header.h deleted file mode 100644 index 24617b39bd..0000000000 --- a/third_party/linux/include/media/cam_sensor_cmn_header.h +++ /dev/null @@ -1,391 +0,0 @@ -/* Copyright (c) 2017-2018, The Linux Foundation. All rights reserved. - * - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License version 2 and - * only version 2 as published by the Free Software Foundation. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - */ - -#ifndef _CAM_SENSOR_CMN_HEADER_ -#define _CAM_SENSOR_CMN_HEADER_ - -#include -#include -#include - -#define MAX_REGULATOR 5 -#define MAX_POWER_CONFIG 12 - -#define MAX_PER_FRAME_ARRAY 32 -#define BATCH_SIZE_MAX 16 - -#define CAM_SENSOR_NAME "cam-sensor" -#define CAM_ACTUATOR_NAME "cam-actuator" -#define CAM_CSIPHY_NAME "cam-csiphy" -#define CAM_FLASH_NAME "cam-flash" -#define CAM_EEPROM_NAME "cam-eeprom" -#define CAM_OIS_NAME "cam-ois" - -#define MAX_SYSTEM_PIPELINE_DELAY 2 - -#define CAM_PKT_NOP_OPCODE 127 - -enum camera_sensor_cmd_type { - CAMERA_SENSOR_CMD_TYPE_INVALID, - CAMERA_SENSOR_CMD_TYPE_PROBE, - CAMERA_SENSOR_CMD_TYPE_PWR_UP, - CAMERA_SENSOR_CMD_TYPE_PWR_DOWN, - CAMERA_SENSOR_CMD_TYPE_I2C_INFO, - CAMERA_SENSOR_CMD_TYPE_I2C_RNDM_WR, - CAMERA_SENSOR_CMD_TYPE_I2C_RNDM_RD, - CAMERA_SENSOR_CMD_TYPE_I2C_CONT_WR, - CAMERA_SENSOR_CMD_TYPE_I2C_CONT_RD, - CAMERA_SENSOR_CMD_TYPE_WAIT, - CAMERA_SENSOR_FLASH_CMD_TYPE_INIT_INFO, - CAMERA_SENSOR_FLASH_CMD_TYPE_FIRE, - CAMERA_SENSOR_FLASH_CMD_TYPE_RER, - CAMERA_SENSOR_FLASH_CMD_TYPE_QUERYCURR, - CAMERA_SENSOR_FLASH_CMD_TYPE_WIDGET, - CAMERA_SENSOR_CMD_TYPE_RD_DATA, - CAMERA_SENSOR_FLASH_CMD_TYPE_INIT_FIRE, - CAMERA_SENSOR_CMD_TYPE_MAX, -}; - -enum camera_sensor_i2c_op_code { - CAMERA_SENSOR_I2C_OP_INVALID, - CAMERA_SENSOR_I2C_OP_RNDM_WR, - CAMERA_SENSOR_I2C_OP_RNDM_WR_VERF, - CAMERA_SENSOR_I2C_OP_CONT_WR_BRST, - CAMERA_SENSOR_I2C_OP_CONT_WR_BRST_VERF, - CAMERA_SENSOR_I2C_OP_CONT_WR_SEQN, - CAMERA_SENSOR_I2C_OP_CONT_WR_SEQN_VERF, - CAMERA_SENSOR_I2C_OP_MAX, -}; - -enum camera_sensor_wait_op_code { - CAMERA_SENSOR_WAIT_OP_INVALID, - CAMERA_SENSOR_WAIT_OP_COND, - CAMERA_SENSOR_WAIT_OP_HW_UCND, - CAMERA_SENSOR_WAIT_OP_SW_UCND, - CAMERA_SENSOR_WAIT_OP_MAX, -}; - -enum camera_flash_opcode { - CAMERA_SENSOR_FLASH_OP_INVALID, - CAMERA_SENSOR_FLASH_OP_OFF, - CAMERA_SENSOR_FLASH_OP_FIRELOW, - CAMERA_SENSOR_FLASH_OP_FIREHIGH, - CAMERA_SENSOR_FLASH_OP_MAX, -}; - -enum camera_sensor_i2c_type { - CAMERA_SENSOR_I2C_TYPE_INVALID, - CAMERA_SENSOR_I2C_TYPE_BYTE, - CAMERA_SENSOR_I2C_TYPE_WORD, - CAMERA_SENSOR_I2C_TYPE_3B, - CAMERA_SENSOR_I2C_TYPE_DWORD, - CAMERA_SENSOR_I2C_TYPE_MAX, -}; - -enum i2c_freq_mode { - I2C_STANDARD_MODE, - I2C_FAST_MODE, - I2C_CUSTOM_MODE, - I2C_FAST_PLUS_MODE, - I2C_MAX_MODES, -}; - -enum position_roll { - ROLL_0 = 0, - ROLL_90 = 90, - ROLL_180 = 180, - ROLL_270 = 270, - ROLL_INVALID = 360, -}; - -enum position_yaw { - FRONT_CAMERA_YAW = 0, - REAR_CAMERA_YAW = 180, - INVALID_YAW = 360, -}; - -enum position_pitch { - LEVEL_PITCH = 0, - INVALID_PITCH = 360, -}; - -enum sensor_sub_module { - SUB_MODULE_SENSOR, - SUB_MODULE_ACTUATOR, - SUB_MODULE_EEPROM, - SUB_MODULE_LED_FLASH, - SUB_MODULE_CSID, - SUB_MODULE_CSIPHY, - SUB_MODULE_OIS, - SUB_MODULE_EXT, - SUB_MODULE_MAX, -}; - -enum msm_camera_power_seq_type { - SENSOR_MCLK, - SENSOR_VANA, - SENSOR_VDIG, - SENSOR_VIO, - SENSOR_VAF, - SENSOR_VAF_PWDM, - SENSOR_CUSTOM_REG1, - SENSOR_CUSTOM_REG2, - SENSOR_RESET, - SENSOR_STANDBY, - SENSOR_CUSTOM_GPIO1, - SENSOR_CUSTOM_GPIO2, - SENSOR_SEQ_TYPE_MAX, -}; - -enum cam_sensor_packet_opcodes { - CAM_SENSOR_PACKET_OPCODE_SENSOR_STREAMON, - CAM_SENSOR_PACKET_OPCODE_SENSOR_UPDATE, - CAM_SENSOR_PACKET_OPCODE_SENSOR_INITIAL_CONFIG, - CAM_SENSOR_PACKET_OPCODE_SENSOR_PROBE, - CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, - CAM_SENSOR_PACKET_OPCODE_SENSOR_STREAMOFF, - CAM_SENSOR_PACKET_OPCODE_SENSOR_NOP = 127 -}; - -enum cam_actuator_packet_opcodes { - CAM_ACTUATOR_PACKET_OPCODE_INIT, - CAM_ACTUATOR_PACKET_AUTO_MOVE_LENS, - CAM_ACTUATOR_PACKET_MANUAL_MOVE_LENS -}; - -enum cam_eeprom_packet_opcodes { - CAM_EEPROM_PACKET_OPCODE_INIT -}; - -enum cam_ois_packet_opcodes { - CAM_OIS_PACKET_OPCODE_INIT, - CAM_OIS_PACKET_OPCODE_OIS_CONTROL -}; - -enum msm_bus_perf_setting { - S_INIT, - S_PREVIEW, - S_VIDEO, - S_CAPTURE, - S_ZSL, - S_STEREO_VIDEO, - S_STEREO_CAPTURE, - S_DEFAULT, - S_LIVESHOT, - S_DUAL, - S_EXIT -}; - -enum msm_camera_device_type_t { - MSM_CAMERA_I2C_DEVICE, - MSM_CAMERA_PLATFORM_DEVICE, - MSM_CAMERA_SPI_DEVICE, -}; - -enum cam_flash_device_type { - CAMERA_FLASH_DEVICE_TYPE_PMIC = 0, - CAMERA_FLASH_DEVICE_TYPE_I2C, - CAMERA_FLASH_DEVICE_TYPE_GPIO, -}; - -enum cci_i2c_master_t { - MASTER_0, - MASTER_1, - MASTER_MAX, -}; - -enum camera_vreg_type { - VREG_TYPE_DEFAULT, - VREG_TYPE_CUSTOM, -}; - -enum cam_sensor_i2c_cmd_type { - CAM_SENSOR_I2C_WRITE_RANDOM, - CAM_SENSOR_I2C_WRITE_BURST, - CAM_SENSOR_I2C_WRITE_SEQ, - CAM_SENSOR_I2C_READ, - CAM_SENSOR_I2C_POLL -}; - -struct common_header { - uint16_t first_word; - uint8_t third_byte; - uint8_t cmd_type; -}; - -struct camera_vreg_t { - const char *reg_name; - int min_voltage; - int max_voltage; - int op_mode; - uint32_t delay; - const char *custom_vreg_name; - enum camera_vreg_type type; -}; - -struct msm_camera_gpio_num_info { - uint16_t gpio_num[SENSOR_SEQ_TYPE_MAX]; - uint8_t valid[SENSOR_SEQ_TYPE_MAX]; -}; - -struct msm_cam_clk_info { - const char *clk_name; - long clk_rate; - uint32_t delay; -}; - -struct msm_pinctrl_info { - struct pinctrl *pinctrl; - struct pinctrl_state *gpio_state_active; - struct pinctrl_state *gpio_state_suspend; - bool use_pinctrl; -}; - -struct cam_sensor_i2c_reg_array { - uint32_t reg_addr; - uint32_t reg_data; - uint32_t delay; - uint32_t data_mask; -}; - -struct cam_sensor_i2c_reg_setting { - struct cam_sensor_i2c_reg_array *reg_setting; - unsigned short size; - enum camera_sensor_i2c_type addr_type; - enum camera_sensor_i2c_type data_type; - unsigned short delay; -}; - -/*struct i2c_settings_list { - struct cam_sensor_i2c_reg_setting i2c_settings; - enum cam_sensor_i2c_cmd_type op_code; - struct list_head list; -}; - -struct i2c_settings_array { - struct list_head list_head; - int32_t is_settings_valid; - int64_t request_id; -}; - -struct i2c_data_settings { - struct i2c_settings_array init_settings; - struct i2c_settings_array config_settings; - struct i2c_settings_array streamon_settings; - struct i2c_settings_array streamoff_settings; - struct i2c_settings_array *per_frame; -};*/ - -struct cam_sensor_power_ctrl_t { - struct device *dev; - struct cam_sensor_power_setting *power_setting; - uint16_t power_setting_size; - struct cam_sensor_power_setting *power_down_setting; - uint16_t power_down_setting_size; - struct msm_camera_gpio_num_info *gpio_num_info; - struct msm_pinctrl_info pinctrl_info; - uint8_t cam_pinctrl_status; -}; - -struct cam_camera_slave_info { - uint16_t sensor_slave_addr; - uint16_t sensor_id_reg_addr; - uint16_t sensor_id; - uint16_t sensor_id_mask; -}; - -struct msm_sensor_init_params { - int modes_supported; - unsigned int sensor_mount_angle; -}; - -enum msm_sensor_camera_id_t { - CAMERA_0, - CAMERA_1, - CAMERA_2, - CAMERA_3, - CAMERA_4, - CAMERA_5, - CAMERA_6, - MAX_CAMERAS, -}; - -struct msm_sensor_id_info_t { - unsigned short sensor_id_reg_addr; - unsigned short sensor_id; - unsigned short sensor_id_mask; -}; - -enum msm_sensor_output_format_t { - MSM_SENSOR_BAYER, - MSM_SENSOR_YCBCR, - MSM_SENSOR_META, -}; - -struct cam_sensor_power_setting { - enum msm_camera_power_seq_type seq_type; - unsigned short seq_val; - long config_val; - unsigned short delay; - void *data[10]; -}; - -struct cam_sensor_board_info { - struct cam_camera_slave_info slave_info; - int32_t sensor_mount_angle; - int32_t secure_mode; - int modes_supported; - int32_t pos_roll; - int32_t pos_yaw; - int32_t pos_pitch; - int32_t subdev_id[SUB_MODULE_MAX]; - int32_t subdev_intf[SUB_MODULE_MAX]; - const char *misc_regulator; - struct cam_sensor_power_ctrl_t power_info; -}; - -enum msm_camera_vreg_name_t { - CAM_VDIG, - CAM_VIO, - CAM_VANA, - CAM_VAF, - CAM_V_CUSTOM1, - CAM_V_CUSTOM2, - CAM_VREG_MAX, -}; - -struct msm_camera_gpio_conf { - void *cam_gpiomux_conf_tbl; - uint8_t cam_gpiomux_conf_tbl_size; - struct gpio *cam_gpio_common_tbl; - uint8_t cam_gpio_common_tbl_size; - struct gpio *cam_gpio_req_tbl; - uint8_t cam_gpio_req_tbl_size; - uint32_t gpio_no_mux; - uint32_t *camera_off_table; - uint8_t camera_off_table_size; - uint32_t *camera_on_table; - uint8_t camera_on_table_size; - struct msm_camera_gpio_num_info *gpio_num_info; -}; - -/*for tof camera Begin*/ -enum EEPROM_DATA_OP_T{ - EEPROM_DEFAULT_DATA = 0, - EEPROM_INIT_DATA, - EEPROM_CONFIG_DATA, - EEPROM_STREAMON_DATA, - EEPROM_STREAMOFF_DATA, - EEPROM_OTHER_DATA, -}; -/*for tof camera End*/ -#endif /* _CAM_SENSOR_CMN_HEADER_ */ diff --git a/third_party/linux/include/media/cam_sync.h b/third_party/linux/include/media/cam_sync.h deleted file mode 100644 index 4a8781fc82..0000000000 --- a/third_party/linux/include/media/cam_sync.h +++ /dev/null @@ -1,134 +0,0 @@ -#ifndef __UAPI_CAM_SYNC_H__ -#define __UAPI_CAM_SYNC_H__ - -#include -#include -#include -#include - -#define CAM_SYNC_DEVICE_NAME "cam_sync_device" - -/* V4L event which user space will subscribe to */ -#define CAM_SYNC_V4L_EVENT (V4L2_EVENT_PRIVATE_START + 0) - -/* Specific event ids to get notified in user space */ -#define CAM_SYNC_V4L_EVENT_ID_CB_TRIG 0 - -/* Size of opaque payload sent to kernel for safekeeping until signal time */ -#define CAM_SYNC_USER_PAYLOAD_SIZE 2 - -/* Device type for sync device needed for device discovery */ -#define CAM_SYNC_DEVICE_TYPE (MEDIA_ENT_F_OLD_BASE) - -#define CAM_SYNC_GET_PAYLOAD_PTR(ev, type) \ - (type *)((char *)ev.u.data + sizeof(struct cam_sync_ev_header)) - -#define CAM_SYNC_GET_HEADER_PTR(ev) \ - ((struct cam_sync_ev_header *)ev.u.data) - -#define CAM_SYNC_STATE_INVALID 0 -#define CAM_SYNC_STATE_ACTIVE 1 -#define CAM_SYNC_STATE_SIGNALED_SUCCESS 2 -#define CAM_SYNC_STATE_SIGNALED_ERROR 3 - -/** - * struct cam_sync_ev_header - Event header for sync event notification - * - * @sync_obj: Sync object - * @status: Status of the object - */ -struct cam_sync_ev_header { - int32_t sync_obj; - int32_t status; -}; - -/** - * struct cam_sync_info - Sync object creation information - * - * @name: Optional string representation of the sync object - * @sync_obj: Sync object returned after creation in kernel - */ -struct cam_sync_info { - char name[64]; - int32_t sync_obj; -}; - -/** - * struct cam_sync_signal - Sync object signaling struct - * - * @sync_obj: Sync object to be signaled - * @sync_state: State of the sync object to which it should be signaled - */ -struct cam_sync_signal { - int32_t sync_obj; - uint32_t sync_state; -}; - -/** - * struct cam_sync_merge - Merge information for sync objects - * - * @sync_objs: Pointer to sync objects - * @num_objs: Number of objects in the array - * @merged: Merged sync object - */ -struct cam_sync_merge { - __u64 sync_objs; - uint32_t num_objs; - int32_t merged; -}; - -/** - * struct cam_sync_userpayload_info - Payload info from user space - * - * @sync_obj: Sync object for which payload has to be registered for - * @reserved: Reserved - * @payload: Pointer to user payload - */ -struct cam_sync_userpayload_info { - int32_t sync_obj; - uint32_t reserved; - __u64 payload[CAM_SYNC_USER_PAYLOAD_SIZE]; -}; - -/** - * struct cam_sync_wait - Sync object wait information - * - * @sync_obj: Sync object to wait on - * @reserved: Reserved - * @timeout_ms: Timeout in milliseconds - */ -struct cam_sync_wait { - int32_t sync_obj; - uint32_t reserved; - uint64_t timeout_ms; -}; - -/** - * struct cam_private_ioctl_arg - Sync driver ioctl argument - * - * @id: IOCTL command id - * @size: Size of command payload - * @result: Result of command execution - * @reserved: Reserved - * @ioctl_ptr: Pointer to user data - */ -struct cam_private_ioctl_arg { - __u32 id; - __u32 size; - __u32 result; - __u32 reserved; - __u64 ioctl_ptr; -}; - -#define CAM_PRIVATE_IOCTL_CMD \ - _IOWR('V', BASE_VIDIOC_PRIVATE, struct cam_private_ioctl_arg) - -#define CAM_SYNC_CREATE 0 -#define CAM_SYNC_DESTROY 1 -#define CAM_SYNC_SIGNAL 2 -#define CAM_SYNC_MERGE 3 -#define CAM_SYNC_REGISTER_PAYLOAD 4 -#define CAM_SYNC_DEREGISTER_PAYLOAD 5 -#define CAM_SYNC_WAIT 6 - -#endif /* __UAPI_CAM_SYNC_H__ */ diff --git a/third_party/linux/include/msm_cam_sensor.h b/third_party/linux/include/msm_cam_sensor.h deleted file mode 100644 index c75d1fd527..0000000000 --- a/third_party/linux/include/msm_cam_sensor.h +++ /dev/null @@ -1,829 +0,0 @@ -#ifndef __LINUX_MSM_CAM_SENSOR_H -#define __LINUX_MSM_CAM_SENSOR_H - -#ifdef MSM_CAMERA_BIONIC -#include -#endif - -//#include -#include "msm_camsensor_sdk.h" - -#include -#include -#ifdef CONFIG_COMPAT -#include -#endif - -#define I2C_SEQ_REG_SETTING_MAX 5 - -#define MSM_SENSOR_MCLK_8HZ 8000000 -#define MSM_SENSOR_MCLK_16HZ 16000000 -#define MSM_SENSOR_MCLK_24HZ 24000000 - -#define MAX_SENSOR_NAME 32 -#define MAX_ACTUATOR_AF_TOTAL_STEPS 1024 - -#define MAX_OIS_MOD_NAME_SIZE 32 -#define MAX_OIS_NAME_SIZE 32 -#define MAX_OIS_REG_SETTINGS 800 - -#define MOVE_NEAR 0 -#define MOVE_FAR 1 - -#define MSM_ACTUATOR_MOVE_SIGNED_FAR -1 -#define MSM_ACTUATOR_MOVE_SIGNED_NEAR 1 - -#define MAX_ACTUATOR_REGION 5 - -#define MAX_EEPROM_NAME 32 - -#define MAX_AF_ITERATIONS 3 -#define MAX_NUMBER_OF_STEPS 47 -#define MAX_REGULATOR 5 - -#define MSM_V4L2_PIX_FMT_META v4l2_fourcc('M', 'E', 'T', 'A') /* META */ -#define MSM_V4L2_PIX_FMT_SBGGR14 v4l2_fourcc('B', 'G', '1', '4') - /* 14 BGBG.. GRGR.. */ -#define MSM_V4L2_PIX_FMT_SGBRG14 v4l2_fourcc('G', 'B', '1', '4') - /* 14 GBGB.. RGRG.. */ -#define MSM_V4L2_PIX_FMT_SGRBG14 v4l2_fourcc('B', 'A', '1', '4') - /* 14 GRGR.. BGBG.. */ -#define MSM_V4L2_PIX_FMT_SRGGB14 v4l2_fourcc('R', 'G', '1', '4') - /* 14 RGRG.. GBGB.. */ - -enum flash_type { - LED_FLASH = 1, - STROBE_FLASH, - GPIO_FLASH -}; - -enum msm_sensor_resolution_t { - MSM_SENSOR_RES_FULL, - MSM_SENSOR_RES_QTR, - MSM_SENSOR_RES_2, - MSM_SENSOR_RES_3, - MSM_SENSOR_RES_4, - MSM_SENSOR_RES_5, - MSM_SENSOR_RES_6, - MSM_SENSOR_RES_7, - MSM_SENSOR_INVALID_RES, -}; - -enum msm_camera_stream_type_t { - MSM_CAMERA_STREAM_PREVIEW, - MSM_CAMERA_STREAM_SNAPSHOT, - MSM_CAMERA_STREAM_VIDEO, - MSM_CAMERA_STREAM_INVALID, -}; - -enum sensor_sub_module_t { - SUB_MODULE_SENSOR, - SUB_MODULE_CHROMATIX, - SUB_MODULE_ACTUATOR, - SUB_MODULE_EEPROM, - SUB_MODULE_LED_FLASH, - SUB_MODULE_STROBE_FLASH, - SUB_MODULE_CSID, - SUB_MODULE_CSID_3D, - SUB_MODULE_CSIPHY, - SUB_MODULE_CSIPHY_3D, - SUB_MODULE_OIS, - SUB_MODULE_EXT, - SUB_MODULE_MAX, -}; - -enum { - MSM_CAMERA_EFFECT_MODE_OFF, - MSM_CAMERA_EFFECT_MODE_MONO, - MSM_CAMERA_EFFECT_MODE_NEGATIVE, - MSM_CAMERA_EFFECT_MODE_SOLARIZE, - MSM_CAMERA_EFFECT_MODE_SEPIA, - MSM_CAMERA_EFFECT_MODE_POSTERIZE, - MSM_CAMERA_EFFECT_MODE_WHITEBOARD, - MSM_CAMERA_EFFECT_MODE_BLACKBOARD, - MSM_CAMERA_EFFECT_MODE_AQUA, - MSM_CAMERA_EFFECT_MODE_EMBOSS, - MSM_CAMERA_EFFECT_MODE_SKETCH, - MSM_CAMERA_EFFECT_MODE_NEON, - MSM_CAMERA_EFFECT_MODE_MAX -}; - -enum { - MSM_CAMERA_WB_MODE_AUTO, - MSM_CAMERA_WB_MODE_CUSTOM, - MSM_CAMERA_WB_MODE_INCANDESCENT, - MSM_CAMERA_WB_MODE_FLUORESCENT, - MSM_CAMERA_WB_MODE_WARM_FLUORESCENT, - MSM_CAMERA_WB_MODE_DAYLIGHT, - MSM_CAMERA_WB_MODE_CLOUDY_DAYLIGHT, - MSM_CAMERA_WB_MODE_TWILIGHT, - MSM_CAMERA_WB_MODE_SHADE, - MSM_CAMERA_WB_MODE_OFF, - MSM_CAMERA_WB_MODE_MAX -}; - -enum { - MSM_CAMERA_SCENE_MODE_OFF, - MSM_CAMERA_SCENE_MODE_AUTO, - MSM_CAMERA_SCENE_MODE_LANDSCAPE, - MSM_CAMERA_SCENE_MODE_SNOW, - MSM_CAMERA_SCENE_MODE_BEACH, - MSM_CAMERA_SCENE_MODE_SUNSET, - MSM_CAMERA_SCENE_MODE_NIGHT, - MSM_CAMERA_SCENE_MODE_PORTRAIT, - MSM_CAMERA_SCENE_MODE_BACKLIGHT, - MSM_CAMERA_SCENE_MODE_SPORTS, - MSM_CAMERA_SCENE_MODE_ANTISHAKE, - MSM_CAMERA_SCENE_MODE_FLOWERS, - MSM_CAMERA_SCENE_MODE_CANDLELIGHT, - MSM_CAMERA_SCENE_MODE_FIREWORKS, - MSM_CAMERA_SCENE_MODE_PARTY, - MSM_CAMERA_SCENE_MODE_NIGHT_PORTRAIT, - MSM_CAMERA_SCENE_MODE_THEATRE, - MSM_CAMERA_SCENE_MODE_ACTION, - MSM_CAMERA_SCENE_MODE_AR, - MSM_CAMERA_SCENE_MODE_FACE_PRIORITY, - MSM_CAMERA_SCENE_MODE_BARCODE, - MSM_CAMERA_SCENE_MODE_HDR, - MSM_CAMERA_SCENE_MODE_MAX -}; - -enum csid_cfg_type_t { - CSID_INIT, - CSID_CFG, - CSID_TESTMODE_CFG, - CSID_RELEASE, -}; - -enum csiphy_cfg_type_t { - CSIPHY_INIT, - CSIPHY_CFG, - CSIPHY_RELEASE, -}; - -enum camera_vreg_type { - VREG_TYPE_DEFAULT, - VREG_TYPE_CUSTOM, -}; - -enum sensor_af_t { - SENSOR_AF_FOCUSSED, - SENSOR_AF_NOT_FOCUSSED, -}; - -enum cci_i2c_master_t { - MASTER_0, - MASTER_1, - MASTER_MAX, -}; - -struct msm_camera_i2c_array_write_config { - struct msm_camera_i2c_reg_setting conf_array; - uint16_t slave_addr; -}; - -struct msm_camera_i2c_read_config { - uint16_t slave_addr; - uint16_t reg_addr; - enum msm_camera_i2c_reg_addr_type addr_type; - enum msm_camera_i2c_data_type data_type; - uint16_t data; -}; - -struct msm_camera_csi2_params { - struct msm_camera_csid_params csid_params; - struct msm_camera_csiphy_params csiphy_params; - uint8_t csi_clk_scale_enable; -}; - -struct msm_camera_csi_lane_params { - uint16_t csi_lane_assign; - uint16_t csi_lane_mask; -}; - -struct csi_lane_params_t { - uint16_t csi_lane_assign; - uint8_t csi_lane_mask; - uint8_t csi_if; - int8_t csid_core[2]; - uint8_t csi_phy_sel; -}; - -struct msm_sensor_info_t { - char sensor_name[MAX_SENSOR_NAME]; - uint32_t session_id; - int32_t subdev_id[SUB_MODULE_MAX]; - int32_t subdev_intf[SUB_MODULE_MAX]; - uint8_t is_mount_angle_valid; - uint32_t sensor_mount_angle; - int modes_supported; - enum camb_position_t position; -}; - -struct camera_vreg_t { - const char *reg_name; - int min_voltage; - int max_voltage; - int op_mode; - uint32_t delay; - const char *custom_vreg_name; - enum camera_vreg_type type; -}; - -struct sensorb_cfg_data { - int cfgtype; - union { - struct msm_sensor_info_t sensor_info; - struct msm_sensor_init_params sensor_init_params; - void *setting; - struct msm_sensor_i2c_sync_params sensor_i2c_sync_params; - } cfg; -}; - -struct csid_cfg_data { - enum csid_cfg_type_t cfgtype; - union { - uint32_t csid_version; - struct msm_camera_csid_params *csid_params; - struct msm_camera_csid_testmode_parms *csid_testmode_params; - } cfg; -}; - -struct csiphy_cfg_data { - enum csiphy_cfg_type_t cfgtype; - union { - struct msm_camera_csiphy_params *csiphy_params; - struct msm_camera_csi_lane_params *csi_lane_params; - } cfg; -}; - -enum eeprom_cfg_type_t { - CFG_EEPROM_GET_INFO, - CFG_EEPROM_GET_CAL_DATA, - CFG_EEPROM_READ_CAL_DATA, - CFG_EEPROM_WRITE_DATA, - CFG_EEPROM_GET_MM_INFO, - CFG_EEPROM_INIT, -}; - -struct eeprom_get_t { - uint32_t num_bytes; -}; - -struct eeprom_read_t { - uint8_t *dbuffer; - uint32_t num_bytes; -}; - -struct eeprom_write_t { - uint8_t *dbuffer; - uint32_t num_bytes; -}; - -struct eeprom_get_cmm_t { - uint32_t cmm_support; - uint32_t cmm_compression; - uint32_t cmm_size; -}; - -struct msm_eeprom_info_t { - struct msm_sensor_power_setting_array *power_setting_array; - enum i2c_freq_mode_t i2c_freq_mode; - struct msm_eeprom_memory_map_array *mem_map_array; -}; - -struct msm_eeprom_cfg_data { - enum eeprom_cfg_type_t cfgtype; - uint8_t is_supported; - union { - char eeprom_name[MAX_SENSOR_NAME]; - struct eeprom_get_t get_data; - struct eeprom_read_t read_data; - struct eeprom_write_t write_data; - struct eeprom_get_cmm_t get_cmm_data; - struct msm_eeprom_info_t eeprom_info; - } cfg; -}; - -#ifdef CONFIG_COMPAT -struct msm_sensor_power_setting32 { - enum msm_sensor_power_seq_type_t seq_type; - uint16_t seq_val; - compat_uint_t config_val; - uint16_t delay; - compat_uptr_t data[10]; -}; - -struct msm_sensor_power_setting_array32 { - struct msm_sensor_power_setting32 power_setting_a[MAX_POWER_CONFIG]; - compat_uptr_t power_setting; - uint16_t size; - struct msm_sensor_power_setting32 - power_down_setting_a[MAX_POWER_CONFIG]; - compat_uptr_t power_down_setting; - uint16_t size_down; -}; - -struct msm_camera_sensor_slave_info32 { - char sensor_name[32]; - char eeprom_name[32]; - char actuator_name[32]; - char ois_name[32]; - char flash_name[32]; - enum msm_sensor_camera_id_t camera_id; - uint16_t slave_addr; - enum i2c_freq_mode_t i2c_freq_mode; - enum msm_camera_i2c_reg_addr_type addr_type; - struct msm_sensor_id_info_t sensor_id_info; - struct msm_sensor_power_setting_array32 power_setting_array; - uint8_t is_init_params_valid; - struct msm_sensor_init_params sensor_init_params; - enum msm_sensor_output_format_t output_format; -}; - -struct msm_camera_csid_lut_params32 { - uint8_t num_cid; - struct msm_camera_csid_vc_cfg vc_cfg_a[MAX_CID]; - compat_uptr_t vc_cfg[MAX_CID]; -}; - -struct msm_camera_csid_params32 { - uint8_t lane_cnt; - uint16_t lane_assign; - uint8_t phy_sel; - uint32_t csi_clk; - struct msm_camera_csid_lut_params32 lut_params; - uint8_t csi_3p_sel; -}; - -struct msm_camera_csi2_params32 { - struct msm_camera_csid_params32 csid_params; - struct msm_camera_csiphy_params csiphy_params; - uint8_t csi_clk_scale_enable; -}; - -struct csid_cfg_data32 { - enum csid_cfg_type_t cfgtype; - union { - uint32_t csid_version; - compat_uptr_t csid_params; - compat_uptr_t csid_testmode_params; - } cfg; -}; - -struct eeprom_read_t32 { - compat_uptr_t dbuffer; - uint32_t num_bytes; -}; - -struct eeprom_write_t32 { - compat_uptr_t dbuffer; - uint32_t num_bytes; -}; - -struct msm_eeprom_info_t32 { - compat_uptr_t power_setting_array; - enum i2c_freq_mode_t i2c_freq_mode; - compat_uptr_t mem_map_array; -}; - -struct msm_eeprom_cfg_data32 { - enum eeprom_cfg_type_t cfgtype; - uint8_t is_supported; - union { - char eeprom_name[MAX_SENSOR_NAME]; - struct eeprom_get_t get_data; - struct eeprom_read_t32 read_data; - struct eeprom_write_t32 write_data; - struct msm_eeprom_info_t32 eeprom_info; - } cfg; -}; - -struct msm_camera_i2c_seq_reg_setting32 { - compat_uptr_t reg_setting; - uint16_t size; - enum msm_camera_i2c_reg_addr_type addr_type; - uint16_t delay; -}; -#endif - -enum msm_sensor_cfg_type_t { - CFG_SET_SLAVE_INFO, - CFG_SLAVE_READ_I2C, - CFG_WRITE_I2C_ARRAY, - CFG_SLAVE_WRITE_I2C_ARRAY, - CFG_WRITE_I2C_SEQ_ARRAY, - CFG_POWER_UP, - CFG_POWER_DOWN, - CFG_SET_STOP_STREAM_SETTING, - CFG_GET_SENSOR_INFO, - CFG_GET_SENSOR_INIT_PARAMS, - CFG_SET_INIT_SETTING, - CFG_SET_RESOLUTION, - CFG_SET_STOP_STREAM, - CFG_SET_START_STREAM, - CFG_SET_SATURATION, - CFG_SET_CONTRAST, - CFG_SET_SHARPNESS, - CFG_SET_ISO, - CFG_SET_EXPOSURE_COMPENSATION, - CFG_SET_ANTIBANDING, - CFG_SET_BESTSHOT_MODE, - CFG_SET_EFFECT, - CFG_SET_WHITE_BALANCE, - CFG_SET_AUTOFOCUS, - CFG_CANCEL_AUTOFOCUS, - CFG_SET_STREAM_TYPE, - CFG_SET_I2C_SYNC_PARAM, - CFG_WRITE_I2C_ARRAY_ASYNC, - CFG_WRITE_I2C_ARRAY_SYNC, - CFG_WRITE_I2C_ARRAY_SYNC_BLOCK, -}; - -enum msm_actuator_cfg_type_t { - CFG_GET_ACTUATOR_INFO, - CFG_SET_ACTUATOR_INFO, - CFG_SET_DEFAULT_FOCUS, - CFG_MOVE_FOCUS, - CFG_SET_POSITION, - CFG_ACTUATOR_POWERDOWN, - CFG_ACTUATOR_POWERUP, - CFG_ACTUATOR_INIT, -}; - -enum msm_ois_cfg_type_t { - CFG_OIS_INIT, - CFG_OIS_POWERDOWN, - CFG_OIS_POWERUP, - CFG_OIS_CONTROL, - CFG_OIS_I2C_WRITE_SEQ_TABLE, -}; - -enum msm_ois_i2c_operation { - MSM_OIS_WRITE = 0, - MSM_OIS_POLL, -}; - -struct reg_settings_ois_t { - uint16_t reg_addr; - enum msm_camera_i2c_reg_addr_type addr_type; - uint32_t reg_data; - enum msm_camera_i2c_data_type data_type; - enum msm_ois_i2c_operation i2c_operation; - uint32_t delay; -#define OIS_REG_DATA_SEQ_MAX 128 - unsigned char reg_data_seq[OIS_REG_DATA_SEQ_MAX]; - uint32_t reg_data_seq_size; -}; - -struct msm_ois_params_t { - uint16_t data_size; - uint16_t setting_size; - uint32_t i2c_addr; - enum i2c_freq_mode_t i2c_freq_mode; - enum msm_camera_i2c_reg_addr_type i2c_addr_type; - enum msm_camera_i2c_data_type i2c_data_type; - struct reg_settings_ois_t *settings; -}; - -struct msm_ois_set_info_t { - struct msm_ois_params_t ois_params; -}; - -struct msm_actuator_move_params_t { - int8_t dir; - int8_t sign_dir; - int16_t dest_step_pos; - int32_t num_steps; - uint16_t curr_lens_pos; - struct damping_params_t *ringing_params; -}; - -struct msm_actuator_tuning_params_t { - int16_t initial_code; - uint16_t pwd_step; - uint16_t region_size; - uint32_t total_steps; - struct region_params_t *region_params; -}; - -struct park_lens_data_t { - uint32_t damping_step; - uint32_t damping_delay; - uint32_t hw_params; - uint32_t max_step; -}; - -struct msm_actuator_params_t { - enum actuator_type act_type; - uint8_t reg_tbl_size; - uint16_t data_size; - uint16_t init_setting_size; - uint32_t i2c_addr; - enum i2c_freq_mode_t i2c_freq_mode; - enum msm_actuator_addr_type i2c_addr_type; - enum msm_actuator_data_type i2c_data_type; - struct msm_actuator_reg_params_t *reg_tbl_params; - struct reg_settings_t *init_settings; - struct park_lens_data_t park_lens; -}; - -struct msm_actuator_set_info_t { - struct msm_actuator_params_t actuator_params; - struct msm_actuator_tuning_params_t af_tuning_params; -}; - -struct msm_actuator_get_info_t { - uint32_t focal_length_num; - uint32_t focal_length_den; - uint32_t f_number_num; - uint32_t f_number_den; - uint32_t f_pix_num; - uint32_t f_pix_den; - uint32_t total_f_dist_num; - uint32_t total_f_dist_den; - uint32_t hor_view_angle_num; - uint32_t hor_view_angle_den; - uint32_t ver_view_angle_num; - uint32_t ver_view_angle_den; -}; - -enum af_camera_name { - ACTUATOR_MAIN_CAM_0, - ACTUATOR_MAIN_CAM_1, - ACTUATOR_MAIN_CAM_2, - ACTUATOR_MAIN_CAM_3, - ACTUATOR_MAIN_CAM_4, - ACTUATOR_MAIN_CAM_5, - ACTUATOR_WEB_CAM_0, - ACTUATOR_WEB_CAM_1, - ACTUATOR_WEB_CAM_2, -}; - -struct msm_ois_cfg_data { - int cfgtype; - union { - struct msm_ois_set_info_t set_info; - struct msm_camera_i2c_seq_reg_setting *settings; - } cfg; -}; - -struct msm_actuator_set_position_t { - uint16_t number_of_steps; - uint32_t hw_params; - uint16_t pos[MAX_NUMBER_OF_STEPS]; - uint16_t delay[MAX_NUMBER_OF_STEPS]; -}; - -struct msm_actuator_cfg_data { - int cfgtype; - uint8_t is_af_supported; - union { - struct msm_actuator_move_params_t move; - struct msm_actuator_set_info_t set_info; - struct msm_actuator_get_info_t get_info; - struct msm_actuator_set_position_t setpos; - enum af_camera_name cam_name; - } cfg; -}; - -enum msm_camera_led_config_t { - MSM_CAMERA_LED_OFF, - MSM_CAMERA_LED_LOW, - MSM_CAMERA_LED_HIGH, - MSM_CAMERA_LED_INIT, - MSM_CAMERA_LED_RELEASE, -}; - -struct msm_camera_led_cfg_t { - enum msm_camera_led_config_t cfgtype; - int32_t torch_current[MAX_LED_TRIGGERS]; - int32_t flash_current[MAX_LED_TRIGGERS]; - int32_t flash_duration[MAX_LED_TRIGGERS]; -}; - -struct msm_flash_init_info_t { - enum msm_flash_driver_type flash_driver_type; - uint32_t slave_addr; - enum i2c_freq_mode_t i2c_freq_mode; - struct msm_sensor_power_setting_array *power_setting_array; - struct msm_camera_i2c_reg_setting_array *settings; -}; - -struct msm_flash_cfg_data_t { - enum msm_flash_cfg_type_t cfg_type; - int32_t flash_current[MAX_LED_TRIGGERS]; - int32_t flash_duration[MAX_LED_TRIGGERS]; - union { - struct msm_flash_init_info_t *flash_init_info; - struct msm_camera_i2c_reg_setting_array *settings; - } cfg; -}; - -/* sensor init structures and enums */ -enum msm_sensor_init_cfg_type_t { - CFG_SINIT_PROBE, - CFG_SINIT_PROBE_DONE, - CFG_SINIT_PROBE_WAIT_DONE, -}; - -struct sensor_init_cfg_data { - enum msm_sensor_init_cfg_type_t cfgtype; - struct msm_sensor_info_t probed_info; - char entity_name[MAX_SENSOR_NAME]; - union { - void *setting; - } cfg; -}; - -#define VIDIOC_MSM_SENSOR_CFG \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 1, struct sensorb_cfg_data) - -#define VIDIOC_MSM_SENSOR_RELEASE \ - _IO('V', BASE_VIDIOC_PRIVATE + 2) - -#define VIDIOC_MSM_SENSOR_GET_SUBDEV_ID \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 3, uint32_t) - -#define VIDIOC_MSM_CSIPHY_IO_CFG \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 4, struct csiphy_cfg_data) - -#define VIDIOC_MSM_CSID_IO_CFG \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 5, struct csid_cfg_data) - -#define VIDIOC_MSM_ACTUATOR_CFG \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 6, struct msm_actuator_cfg_data) - -#define VIDIOC_MSM_FLASH_LED_DATA_CFG \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 7, struct msm_camera_led_cfg_t) - -#define VIDIOC_MSM_EEPROM_CFG \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 8, struct msm_eeprom_cfg_data) - -#define VIDIOC_MSM_SENSOR_GET_AF_STATUS \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 9, uint32_t) - -#define VIDIOC_MSM_SENSOR_INIT_CFG \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 10, struct sensor_init_cfg_data) - -#define VIDIOC_MSM_OIS_CFG \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 11, struct msm_ois_cfg_data) - -#define VIDIOC_MSM_FLASH_CFG \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 13, struct msm_flash_cfg_data_t) - -#ifdef CONFIG_COMPAT -struct msm_camera_i2c_reg_setting32 { - compat_uptr_t reg_setting; - uint16_t size; - enum msm_camera_i2c_reg_addr_type addr_type; - enum msm_camera_i2c_data_type data_type; - uint16_t delay; -}; - -struct msm_camera_i2c_array_write_config32 { - struct msm_camera_i2c_reg_setting32 conf_array; - uint16_t slave_addr; -}; - -struct msm_actuator_tuning_params_t32 { - int16_t initial_code; - uint16_t pwd_step; - uint16_t region_size; - uint32_t total_steps; - compat_uptr_t region_params; -}; - -struct msm_actuator_params_t32 { - enum actuator_type act_type; - uint8_t reg_tbl_size; - uint16_t data_size; - uint16_t init_setting_size; - uint32_t i2c_addr; - enum i2c_freq_mode_t i2c_freq_mode; - enum msm_actuator_addr_type i2c_addr_type; - enum msm_actuator_data_type i2c_data_type; - compat_uptr_t reg_tbl_params; - compat_uptr_t init_settings; - struct park_lens_data_t park_lens; -}; - -struct msm_actuator_set_info_t32 { - struct msm_actuator_params_t32 actuator_params; - struct msm_actuator_tuning_params_t32 af_tuning_params; -}; - -struct sensor_init_cfg_data32 { - enum msm_sensor_init_cfg_type_t cfgtype; - struct msm_sensor_info_t probed_info; - char entity_name[MAX_SENSOR_NAME]; - union { - compat_uptr_t setting; - } cfg; -}; - -struct msm_actuator_move_params_t32 { - int8_t dir; - int8_t sign_dir; - int16_t dest_step_pos; - int32_t num_steps; - uint16_t curr_lens_pos; - compat_uptr_t ringing_params; -}; - -struct msm_actuator_cfg_data32 { - int cfgtype; - uint8_t is_af_supported; - union { - struct msm_actuator_move_params_t32 move; - struct msm_actuator_set_info_t32 set_info; - struct msm_actuator_get_info_t get_info; - struct msm_actuator_set_position_t setpos; - enum af_camera_name cam_name; - } cfg; -}; - -struct csiphy_cfg_data32 { - enum csiphy_cfg_type_t cfgtype; - union { - compat_uptr_t csiphy_params; - compat_uptr_t csi_lane_params; - } cfg; -}; - -struct sensorb_cfg_data32 { - int cfgtype; - union { - struct msm_sensor_info_t sensor_info; - struct msm_sensor_init_params sensor_init_params; - compat_uptr_t setting; - struct msm_sensor_i2c_sync_params sensor_i2c_sync_params; - } cfg; -}; - -struct msm_ois_params_t32 { - uint16_t data_size; - uint16_t setting_size; - uint32_t i2c_addr; - enum i2c_freq_mode_t i2c_freq_mode; - enum msm_camera_i2c_reg_addr_type i2c_addr_type; - enum msm_camera_i2c_data_type i2c_data_type; - compat_uptr_t settings; -}; - -struct msm_ois_set_info_t32 { - struct msm_ois_params_t32 ois_params; -}; - -struct msm_ois_cfg_data32 { - int cfgtype; - union { - struct msm_ois_set_info_t32 set_info; - compat_uptr_t settings; - } cfg; -}; - -struct msm_flash_init_info_t32 { - enum msm_flash_driver_type flash_driver_type; - uint32_t slave_addr; - enum i2c_freq_mode_t i2c_freq_mode; - compat_uptr_t power_setting_array; - compat_uptr_t settings; -}; - -struct msm_flash_cfg_data_t32 { - enum msm_flash_cfg_type_t cfg_type; - int32_t flash_current[MAX_LED_TRIGGERS]; - int32_t flash_duration[MAX_LED_TRIGGERS]; - union { - compat_uptr_t flash_init_info; - compat_uptr_t settings; - } cfg; -}; - -#define VIDIOC_MSM_ACTUATOR_CFG32 \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 6, struct msm_actuator_cfg_data32) - -#define VIDIOC_MSM_SENSOR_INIT_CFG32 \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 10, struct sensor_init_cfg_data32) - -#define VIDIOC_MSM_CSIPHY_IO_CFG32 \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 4, struct csiphy_cfg_data32) - -#define VIDIOC_MSM_SENSOR_CFG32 \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 1, struct sensorb_cfg_data32) - -#define VIDIOC_MSM_EEPROM_CFG32 \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 8, struct msm_eeprom_cfg_data32) - -#define VIDIOC_MSM_OIS_CFG32 \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 11, struct msm_ois_cfg_data32) - -#define VIDIOC_MSM_CSID_IO_CFG32 \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 5, struct csid_cfg_data32) - -#define VIDIOC_MSM_FLASH_CFG32 \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 13, struct msm_flash_cfg_data_t32) -#endif - -#endif /* __LINUX_MSM_CAM_SENSOR_H */ diff --git a/third_party/linux/include/msm_camsensor_sdk.h b/third_party/linux/include/msm_camsensor_sdk.h deleted file mode 100644 index 62a4da253c..0000000000 --- a/third_party/linux/include/msm_camsensor_sdk.h +++ /dev/null @@ -1,386 +0,0 @@ -#ifndef __LINUX_MSM_CAMSENSOR_SDK_H -#define __LINUX_MSM_CAMSENSOR_SDK_H - -#define KVERSION 0x1 - -#define MAX_POWER_CONFIG 12 -#define GPIO_OUT_LOW (0 << 1) -#define GPIO_OUT_HIGH (1 << 1) -#define CSI_EMBED_DATA 0x12 -#define CSI_RESERVED_DATA_0 0x13 -#define CSI_YUV422_8 0x1E -#define CSI_RAW8 0x2A -#define CSI_RAW10 0x2B -#define CSI_RAW12 0x2C -#define CSI_DECODE_6BIT 0 -#define CSI_DECODE_8BIT 1 -#define CSI_DECODE_10BIT 2 -#define CSI_DECODE_12BIT 3 -#define CSI_DECODE_DPCM_10_8_10 5 -#define MAX_CID 16 -#define I2C_SEQ_REG_DATA_MAX 1024 -#define I2C_REG_DATA_MAX (8*1024) - -#define MSM_V4L2_PIX_FMT_META v4l2_fourcc('M', 'E', 'T', 'A') /* META */ -#define MSM_V4L2_PIX_FMT_SBGGR14 v4l2_fourcc('B', 'G', '1', '4') - /* 14 BGBG.. GRGR.. */ -#define MSM_V4L2_PIX_FMT_SGBRG14 v4l2_fourcc('G', 'B', '1', '4') - /* 14 GBGB.. RGRG.. */ -#define MSM_V4L2_PIX_FMT_SGRBG14 v4l2_fourcc('B', 'A', '1', '4') - /* 14 GRGR.. BGBG.. */ -#define MSM_V4L2_PIX_FMT_SRGGB14 v4l2_fourcc('R', 'G', '1', '4') - /* 14 RGRG.. GBGB.. */ - -#define MAX_ACTUATOR_REG_TBL_SIZE 8 -#define MAX_ACTUATOR_REGION 5 -#define NUM_ACTUATOR_DIR 2 -#define MAX_ACTUATOR_SCENARIO 8 -#define MAX_ACT_MOD_NAME_SIZE 32 -#define MAX_ACT_NAME_SIZE 32 -#define MAX_ACTUATOR_INIT_SET 120 -#define MAX_I2C_REG_SET 12 - -#define MAX_LED_TRIGGERS 3 - -#define MSM_EEPROM_MEMORY_MAP_MAX_SIZE 80 -#define MSM_EEPROM_MAX_MEM_MAP_CNT 8 - -enum msm_sensor_camera_id_t { - CAMERA_0, - CAMERA_1, - CAMERA_2, - CAMERA_3, - MAX_CAMERAS, -}; - -enum i2c_freq_mode_t { - I2C_STANDARD_MODE, - I2C_FAST_MODE, - I2C_CUSTOM_MODE, - I2C_FAST_PLUS_MODE, - I2C_MAX_MODES, -}; - -enum camb_position_t { - BACK_CAMERA_B, - FRONT_CAMERA_B, - AUX_CAMERA_B = 0x100, - INVALID_CAMERA_B, -}; - -enum msm_sensor_power_seq_type_t { - SENSOR_CLK, - SENSOR_GPIO, - SENSOR_VREG, - SENSOR_I2C_MUX, - SENSOR_I2C, -}; - -enum msm_camera_i2c_reg_addr_type { - MSM_CAMERA_I2C_BYTE_ADDR = 1, - MSM_CAMERA_I2C_WORD_ADDR, - MSM_CAMERA_I2C_3B_ADDR, - MSM_CAMERA_I2C_ADDR_TYPE_MAX, -}; - -enum msm_camera_i2c_data_type { - MSM_CAMERA_I2C_BYTE_DATA = 1, - MSM_CAMERA_I2C_WORD_DATA, - MSM_CAMERA_I2C_DWORD_DATA, - MSM_CAMERA_I2C_SET_BYTE_MASK, - MSM_CAMERA_I2C_UNSET_BYTE_MASK, - MSM_CAMERA_I2C_SET_WORD_MASK, - MSM_CAMERA_I2C_UNSET_WORD_MASK, - MSM_CAMERA_I2C_SET_BYTE_WRITE_MASK_DATA, - MSM_CAMERA_I2C_SEQ_DATA, - MSM_CAMERA_I2C_DATA_TYPE_MAX, -}; - -enum msm_sensor_power_seq_gpio_t { - SENSOR_GPIO_RESET, - SENSOR_GPIO_STANDBY, - SENSOR_GPIO_AF_PWDM, - SENSOR_GPIO_VIO, - SENSOR_GPIO_VANA, - SENSOR_GPIO_VDIG, - SENSOR_GPIO_VAF, - SENSOR_GPIO_FL_EN, - SENSOR_GPIO_FL_NOW, - SENSOR_GPIO_FL_RESET, - SENSOR_GPIO_CUSTOM1, - SENSOR_GPIO_CUSTOM2, - SENSOR_GPIO_MAX, -}; - -enum msm_camera_vreg_name_t { - CAM_VDIG, - CAM_VIO, - CAM_VANA, - CAM_VAF, - CAM_V_CUSTOM1, - CAM_V_CUSTOM2, - CAM_VREG_MAX, -}; - -enum msm_sensor_clk_type_t { - SENSOR_CAM_MCLK, - SENSOR_CAM_CLK, - SENSOR_CAM_CLK_MAX, -}; - -enum camerab_mode_t { - CAMERA_MODE_2D_B = (1<<0), - CAMERA_MODE_3D_B = (1<<1), - CAMERA_MODE_INVALID = (1<<2), -}; - -enum msm_actuator_data_type { - MSM_ACTUATOR_BYTE_DATA = 1, - MSM_ACTUATOR_WORD_DATA, -}; - -enum msm_actuator_addr_type { - MSM_ACTUATOR_BYTE_ADDR = 1, - MSM_ACTUATOR_WORD_ADDR, -}; - -enum msm_actuator_write_type { - MSM_ACTUATOR_WRITE_HW_DAMP, - MSM_ACTUATOR_WRITE_DAC, - MSM_ACTUATOR_WRITE, - MSM_ACTUATOR_WRITE_DIR_REG, - MSM_ACTUATOR_POLL, - MSM_ACTUATOR_READ_WRITE, -}; - -enum msm_actuator_i2c_operation { - MSM_ACT_WRITE = 0, - MSM_ACT_POLL, -}; - -enum actuator_type { - ACTUATOR_VCM, - ACTUATOR_PIEZO, - ACTUATOR_HVCM, - ACTUATOR_BIVCM, -}; - -enum msm_flash_driver_type { - FLASH_DRIVER_PMIC, - FLASH_DRIVER_I2C, - FLASH_DRIVER_GPIO, - FLASH_DRIVER_DEFAULT -}; - -enum msm_flash_cfg_type_t { - CFG_FLASH_INIT, - CFG_FLASH_RELEASE, - CFG_FLASH_OFF, - CFG_FLASH_LOW, - CFG_FLASH_HIGH, -}; - -enum msm_sensor_output_format_t { - MSM_SENSOR_BAYER, - MSM_SENSOR_YCBCR, - MSM_SENSOR_META, -}; - -struct msm_sensor_power_setting { - enum msm_sensor_power_seq_type_t seq_type; - unsigned short seq_val; - long config_val; - unsigned short delay; - void *data[10]; -}; - -struct msm_sensor_power_setting_array { - struct msm_sensor_power_setting power_setting_a[MAX_POWER_CONFIG]; - struct msm_sensor_power_setting *power_setting; - unsigned short size; - struct msm_sensor_power_setting power_down_setting_a[MAX_POWER_CONFIG]; - struct msm_sensor_power_setting *power_down_setting; - unsigned short size_down; -}; - -enum msm_camera_i2c_operation { - MSM_CAM_WRITE = 0, - MSM_CAM_POLL, - MSM_CAM_READ, -}; - -struct msm_sensor_i2c_sync_params { - unsigned int cid; - int csid; - unsigned short line; - unsigned short delay; -}; - -struct msm_camera_reg_settings_t { - uint16_t reg_addr; - enum msm_camera_i2c_reg_addr_type addr_type; - uint16_t reg_data; - enum msm_camera_i2c_data_type data_type; - enum msm_camera_i2c_operation i2c_operation; - uint16_t delay; -}; - -struct msm_eeprom_mem_map_t { - int slave_addr; - struct msm_camera_reg_settings_t - mem_settings[MSM_EEPROM_MEMORY_MAP_MAX_SIZE]; - int memory_map_size; -}; - -struct msm_eeprom_memory_map_array { - struct msm_eeprom_mem_map_t memory_map[MSM_EEPROM_MAX_MEM_MAP_CNT]; - uint32_t msm_size_of_max_mappings; -}; - -struct msm_sensor_init_params { - /* mask of modes supported: 2D, 3D */ - int modes_supported; - /* sensor position: front, back */ - enum camb_position_t position; - /* sensor mount angle */ - unsigned int sensor_mount_angle; -}; - -struct msm_sensor_id_info_t { - unsigned short sensor_id_reg_addr; - unsigned short sensor_id; - unsigned short sensor_id_mask; - // added in LeEco - unsigned char module_id; - unsigned char vcm_id; -}; - -struct msm_camera_sensor_slave_info { - char sensor_name[32]; - char eeprom_name[32]; - char actuator_name[32]; - char ois_name[32]; - char flash_name[32]; - enum msm_sensor_camera_id_t camera_id; - unsigned short slave_addr; - enum i2c_freq_mode_t i2c_freq_mode; - enum msm_camera_i2c_reg_addr_type addr_type; - struct msm_sensor_id_info_t sensor_id_info; - struct msm_sensor_power_setting_array power_setting_array; - unsigned char is_init_params_valid; - struct msm_sensor_init_params sensor_init_params; - enum msm_sensor_output_format_t output_format; -}; - -struct msm_camera_i2c_reg_array { - unsigned short reg_addr; - unsigned short reg_data; - unsigned int delay; -}; - -struct msm_camera_i2c_reg_setting { - struct msm_camera_i2c_reg_array *reg_setting; - unsigned short size; - enum msm_camera_i2c_reg_addr_type addr_type; - enum msm_camera_i2c_data_type data_type; - unsigned short delay; -}; - -struct msm_camera_csid_vc_cfg { - unsigned char cid; - unsigned char dt; - unsigned char decode_format; -}; - -struct msm_camera_csid_lut_params { - unsigned char num_cid; - struct msm_camera_csid_vc_cfg vc_cfg_a[MAX_CID]; - struct msm_camera_csid_vc_cfg *vc_cfg[MAX_CID]; -}; - -struct msm_camera_csid_params { - unsigned char lane_cnt; - unsigned short lane_assign; - unsigned char phy_sel; - unsigned int csi_clk; - struct msm_camera_csid_lut_params lut_params; - unsigned char csi_3p_sel; -}; - -struct msm_camera_csid_testmode_parms { - unsigned int num_bytes_per_line; - unsigned int num_lines; - unsigned int h_blanking_count; - unsigned int v_blanking_count; - unsigned int payload_mode; -}; - -struct msm_camera_csiphy_params { - unsigned char lane_cnt; - unsigned char settle_cnt; - unsigned short lane_mask; - unsigned char combo_mode; - unsigned char csid_core; - unsigned int csiphy_clk; - unsigned char csi_3phase; -}; - -struct msm_camera_i2c_seq_reg_array { - unsigned short reg_addr; - unsigned char reg_data[I2C_SEQ_REG_DATA_MAX]; - unsigned short reg_data_size; -}; - -struct msm_camera_i2c_seq_reg_setting { - struct msm_camera_i2c_seq_reg_array *reg_setting; - unsigned short size; - enum msm_camera_i2c_reg_addr_type addr_type; - unsigned short delay; -}; - -struct msm_actuator_reg_params_t { - enum msm_actuator_write_type reg_write_type; - unsigned int hw_mask; - unsigned short reg_addr; - unsigned short hw_shift; - unsigned short data_shift; - unsigned short data_type; - unsigned short addr_type; - unsigned short reg_data; - unsigned short delay; -}; - - -struct damping_params_t { - unsigned int damping_step; - unsigned int damping_delay; - unsigned int hw_params; -}; - -struct region_params_t { - /* [0] = ForwardDirection Macro boundary - [1] = ReverseDirection Inf boundary - */ - unsigned short step_bound[2]; - unsigned short code_per_step; - /* qvalue for converting float type numbers to integer format */ - unsigned int qvalue; -}; - -struct reg_settings_t { - unsigned short reg_addr; - enum msm_actuator_addr_type addr_type; - unsigned short reg_data; - enum msm_actuator_data_type data_type; - enum msm_actuator_i2c_operation i2c_operation; - unsigned int delay; -}; - -struct msm_camera_i2c_reg_setting_array { - struct msm_camera_i2c_reg_array reg_setting_a[MAX_I2C_REG_SET]; - unsigned short size; - enum msm_camera_i2c_reg_addr_type addr_type; - enum msm_camera_i2c_data_type data_type; - unsigned short delay; -}; -#endif /* __LINUX_MSM_CAM_SENSOR_H */ diff --git a/third_party/linux/include/msm_ion.h b/third_party/linux/include/msm_ion.h deleted file mode 100644 index d5caed5eb3..0000000000 --- a/third_party/linux/include/msm_ion.h +++ /dev/null @@ -1,211 +0,0 @@ -#ifndef _UAPI_MSM_ION_H -#define _UAPI_MSM_ION_H - -#include - -enum msm_ion_heap_types { - ION_HEAP_TYPE_MSM_START = ION_HEAP_TYPE_CUSTOM + 1, - ION_HEAP_TYPE_SECURE_DMA = ION_HEAP_TYPE_MSM_START, - ION_HEAP_TYPE_SYSTEM_SECURE, - ION_HEAP_TYPE_HYP_CMA, - /* - * if you add a heap type here you should also add it to - * heap_types_info[] in msm_ion.c - */ -}; - -/** - * These are the only ids that should be used for Ion heap ids. - * The ids listed are the order in which allocation will be attempted - * if specified. Don't swap the order of heap ids unless you know what - * you are doing! - * Id's are spaced by purpose to allow new Id's to be inserted in-between (for - * possible fallbacks) - */ - -enum ion_heap_ids { - INVALID_HEAP_ID = -1, - ION_CP_MM_HEAP_ID = 8, - ION_SECURE_HEAP_ID = 9, - ION_SECURE_DISPLAY_HEAP_ID = 10, - ION_CP_MFC_HEAP_ID = 12, - ION_CP_WB_HEAP_ID = 16, /* 8660 only */ - ION_CAMERA_HEAP_ID = 20, /* 8660 only */ - ION_SYSTEM_CONTIG_HEAP_ID = 21, - ION_ADSP_HEAP_ID = 22, - ION_PIL1_HEAP_ID = 23, /* Currently used for other PIL images */ - ION_SF_HEAP_ID = 24, - ION_SYSTEM_HEAP_ID = 25, - ION_PIL2_HEAP_ID = 26, /* Currently used for modem firmware images */ - ION_QSECOM_HEAP_ID = 27, - ION_AUDIO_HEAP_ID = 28, - - ION_MM_FIRMWARE_HEAP_ID = 29, - - ION_HEAP_ID_RESERVED = 31 /** Bit reserved for ION_FLAG_SECURE flag */ -}; - -/* - * The IOMMU heap is deprecated! Here are some aliases for backwards - * compatibility: - */ -#define ION_IOMMU_HEAP_ID ION_SYSTEM_HEAP_ID -#define ION_HEAP_TYPE_IOMMU ION_HEAP_TYPE_SYSTEM - -enum ion_fixed_position { - NOT_FIXED, - FIXED_LOW, - FIXED_MIDDLE, - FIXED_HIGH, -}; - -enum cp_mem_usage { - VIDEO_BITSTREAM = 0x1, - VIDEO_PIXEL = 0x2, - VIDEO_NONPIXEL = 0x3, - DISPLAY_SECURE_CP_USAGE = 0x4, - CAMERA_SECURE_CP_USAGE = 0x5, - MAX_USAGE = 0x6, - UNKNOWN = 0x7FFFFFFF, -}; - -/** - * Flags to be used when allocating from the secure heap for - * content protection - */ -#define ION_FLAG_CP_TOUCH (1 << 17) -#define ION_FLAG_CP_BITSTREAM (1 << 18) -#define ION_FLAG_CP_PIXEL (1 << 19) -#define ION_FLAG_CP_NON_PIXEL (1 << 20) -#define ION_FLAG_CP_CAMERA (1 << 21) -#define ION_FLAG_CP_HLOS (1 << 22) -#define ION_FLAG_CP_HLOS_FREE (1 << 23) -#define ION_FLAG_CP_SEC_DISPLAY (1 << 25) -#define ION_FLAG_CP_APP (1 << 26) - -/** - * Flag to allow non continguous allocation of memory from secure - * heap - */ -#define ION_FLAG_ALLOW_NON_CONTIG (1 << 24) - -/** - * Flag to use when allocating to indicate that a heap is secure. - */ -#define ION_FLAG_SECURE (1 << ION_HEAP_ID_RESERVED) - -/** - * Flag for clients to force contiguous memort allocation - * - * Use of this flag is carefully monitored! - */ -#define ION_FLAG_FORCE_CONTIGUOUS (1 << 30) - -/* - * Used in conjunction with heap which pool memory to force an allocation - * to come from the page allocator directly instead of from the pool allocation - */ -#define ION_FLAG_POOL_FORCE_ALLOC (1 << 16) - - -#define ION_FLAG_POOL_PREFETCH (1 << 27) - -/** -* Deprecated! Please use the corresponding ION_FLAG_* -*/ -#define ION_SECURE ION_FLAG_SECURE -#define ION_FORCE_CONTIGUOUS ION_FLAG_FORCE_CONTIGUOUS - -/** - * Macro should be used with ion_heap_ids defined above. - */ -#define ION_HEAP(bit) (1 << (bit)) - -#define ION_ADSP_HEAP_NAME "adsp" -#define ION_SYSTEM_HEAP_NAME "system" -#define ION_VMALLOC_HEAP_NAME ION_SYSTEM_HEAP_NAME -#define ION_KMALLOC_HEAP_NAME "kmalloc" -#define ION_AUDIO_HEAP_NAME "audio" -#define ION_SF_HEAP_NAME "sf" -#define ION_MM_HEAP_NAME "mm" -#define ION_CAMERA_HEAP_NAME "camera_preview" -#define ION_IOMMU_HEAP_NAME "iommu" -#define ION_MFC_HEAP_NAME "mfc" -#define ION_WB_HEAP_NAME "wb" -#define ION_MM_FIRMWARE_HEAP_NAME "mm_fw" -#define ION_PIL1_HEAP_NAME "pil_1" -#define ION_PIL2_HEAP_NAME "pil_2" -#define ION_QSECOM_HEAP_NAME "qsecom" -#define ION_SECURE_HEAP_NAME "secure_heap" -#define ION_SECURE_DISPLAY_HEAP_NAME "secure_display" - -#define ION_SET_CACHED(__cache) (__cache | ION_FLAG_CACHED) -#define ION_SET_UNCACHED(__cache) (__cache & ~ION_FLAG_CACHED) - -#define ION_IS_CACHED(__flags) ((__flags) & ION_FLAG_CACHED) - -/* struct ion_flush_data - data passed to ion for flushing caches - * - * @handle: handle with data to flush - * @fd: fd to flush - * @vaddr: userspace virtual address mapped with mmap - * @offset: offset into the handle to flush - * @length: length of handle to flush - * - * Performs cache operations on the handle. If p is the start address - * of the handle, p + offset through p + offset + length will have - * the cache operations performed - */ -struct ion_flush_data { - ion_user_handle_t handle; - int fd; - void *vaddr; - unsigned int offset; - unsigned int length; -}; - -struct ion_prefetch_regions { - unsigned int vmid; - size_t *sizes; - unsigned int nr_sizes; -}; - -struct ion_prefetch_data { - int heap_id; - unsigned long len; - /* Is unsigned long bad? 32bit compiler vs 64 bit compiler*/ - struct ion_prefetch_regions *regions; - unsigned int nr_regions; -}; - -#define ION_IOC_MSM_MAGIC 'M' - -/** - * DOC: ION_IOC_CLEAN_CACHES - clean the caches - * - * Clean the caches of the handle specified. - */ -#define ION_IOC_CLEAN_CACHES _IOWR(ION_IOC_MSM_MAGIC, 0, \ - struct ion_flush_data) -/** - * DOC: ION_IOC_INV_CACHES - invalidate the caches - * - * Invalidate the caches of the handle specified. - */ -#define ION_IOC_INV_CACHES _IOWR(ION_IOC_MSM_MAGIC, 1, \ - struct ion_flush_data) -/** - * DOC: ION_IOC_CLEAN_INV_CACHES - clean and invalidate the caches - * - * Clean and invalidate the caches of the handle specified. - */ -#define ION_IOC_CLEAN_INV_CACHES _IOWR(ION_IOC_MSM_MAGIC, 2, \ - struct ion_flush_data) - -#define ION_IOC_PREFETCH _IOWR(ION_IOC_MSM_MAGIC, 3, \ - struct ion_prefetch_data) - -#define ION_IOC_DRAIN _IOWR(ION_IOC_MSM_MAGIC, 4, \ - struct ion_prefetch_data) - -#endif diff --git a/third_party/linux/include/msm_kgsl.h b/third_party/linux/include/msm_kgsl.h deleted file mode 100644 index 93582eb066..0000000000 --- a/third_party/linux/include/msm_kgsl.h +++ /dev/null @@ -1,1449 +0,0 @@ -#ifndef _UAPI_MSM_KGSL_H -#define _UAPI_MSM_KGSL_H - -#include -#include - -/* - * The KGSL version has proven not to be very useful in userspace if features - * are cherry picked into other trees out of order so it is frozen as of 3.14. - * It is left here for backwards compatabilty and as a reminder that - * software releases are never linear. Also, I like pie. - */ - -#define KGSL_VERSION_MAJOR 3 -#define KGSL_VERSION_MINOR 14 - -/* - * We have traditionally mixed context and issueibcmds / command batch flags - * together into a big flag stew. This worked fine until we started adding a - * lot more command batch flags and we started running out of bits. Turns out - * we have a bit of room in the context type / priority mask that we could use - * for command batches, but that means we need to split out the flags into two - * coherent sets. - * - * If any future definitions are for both context and cmdbatch add both defines - * and link the cmdbatch to the context define as we do below. Otherwise feel - * free to add exclusive bits to either set. - */ - -/* --- context flags --- */ -#define KGSL_CONTEXT_SAVE_GMEM 0x00000001 -#define KGSL_CONTEXT_NO_GMEM_ALLOC 0x00000002 -/* This is a cmdbatch exclusive flag - use the CMDBATCH equivalent instead */ -#define KGSL_CONTEXT_SUBMIT_IB_LIST 0x00000004 -#define KGSL_CONTEXT_CTX_SWITCH 0x00000008 -#define KGSL_CONTEXT_PREAMBLE 0x00000010 -#define KGSL_CONTEXT_TRASH_STATE 0x00000020 -#define KGSL_CONTEXT_PER_CONTEXT_TS 0x00000040 -#define KGSL_CONTEXT_USER_GENERATED_TS 0x00000080 -/* This is a cmdbatch exclusive flag - use the CMDBATCH equivalent instead */ -#define KGSL_CONTEXT_END_OF_FRAME 0x00000100 -#define KGSL_CONTEXT_NO_FAULT_TOLERANCE 0x00000200 -/* This is a cmdbatch exclusive flag - use the CMDBATCH equivalent instead */ -#define KGSL_CONTEXT_SYNC 0x00000400 -#define KGSL_CONTEXT_PWR_CONSTRAINT 0x00000800 - -#define KGSL_CONTEXT_PRIORITY_MASK 0x0000F000 -#define KGSL_CONTEXT_PRIORITY_SHIFT 12 -#define KGSL_CONTEXT_PRIORITY_UNDEF 0 - -#define KGSL_CONTEXT_IFH_NOP 0x00010000 -#define KGSL_CONTEXT_SECURE 0x00020000 - -#define KGSL_CONTEXT_PREEMPT_STYLE_MASK 0x0E000000 -#define KGSL_CONTEXT_PREEMPT_STYLE_SHIFT 25 -#define KGSL_CONTEXT_PREEMPT_STYLE_DEFAULT 0x0 -#define KGSL_CONTEXT_PREEMPT_STYLE_RINGBUFFER 0x1 -#define KGSL_CONTEXT_PREEMPT_STYLE_FINEGRAIN 0x2 - -#define KGSL_CONTEXT_TYPE_MASK 0x01F00000 -#define KGSL_CONTEXT_TYPE_SHIFT 20 -#define KGSL_CONTEXT_TYPE_ANY 0 -#define KGSL_CONTEXT_TYPE_GL 1 -#define KGSL_CONTEXT_TYPE_CL 2 -#define KGSL_CONTEXT_TYPE_C2D 3 -#define KGSL_CONTEXT_TYPE_RS 4 -#define KGSL_CONTEXT_TYPE_UNKNOWN 0x1E - -#define KGSL_CONTEXT_INVALID 0xffffffff - -/* - * --- command batch flags --- - * The bits that are linked to a KGSL_CONTEXT equivalent are either legacy - * definitions or bits that are valid for both contexts and cmdbatches. To be - * safe the other 8 bits that are still available in the context field should be - * omitted here in case we need to share - the other bits are available for - * cmdbatch only flags as needed - */ -#define KGSL_CMDBATCH_MEMLIST 0x00000001 -#define KGSL_CMDBATCH_MARKER 0x00000002 -#define KGSL_CMDBATCH_SUBMIT_IB_LIST KGSL_CONTEXT_SUBMIT_IB_LIST /* 0x004 */ -#define KGSL_CMDBATCH_CTX_SWITCH KGSL_CONTEXT_CTX_SWITCH /* 0x008 */ -#define KGSL_CMDBATCH_PROFILING 0x00000010 -#define KGSL_CMDBATCH_PROFILING_KTIME 0x00000020 -#define KGSL_CMDBATCH_END_OF_FRAME KGSL_CONTEXT_END_OF_FRAME /* 0x100 */ -#define KGSL_CMDBATCH_SYNC KGSL_CONTEXT_SYNC /* 0x400 */ -#define KGSL_CMDBATCH_PWR_CONSTRAINT KGSL_CONTEXT_PWR_CONSTRAINT /* 0x800 */ - -/* - * Reserve bits [16:19] and bits [28:31] for possible bits shared between - * contexts and command batches. Update this comment as new flags are added. - */ - -/* - * gpu_command_object flags - these flags communicate the type of command or - * memory object being submitted for a GPU command - */ - -/* Flags for GPU command objects */ -#define KGSL_CMDLIST_IB 0x00000001U -#define KGSL_CMDLIST_CTXTSWITCH_PREAMBLE 0x00000002U -#define KGSL_CMDLIST_IB_PREAMBLE 0x00000004U - -/* Flags for GPU command memory objects */ -#define KGSL_OBJLIST_MEMOBJ 0x00000008U -#define KGSL_OBJLIST_PROFILE 0x00000010U - -/* Flags for GPU command sync points */ -#define KGSL_CMD_SYNCPOINT_TYPE_TIMESTAMP 0 -#define KGSL_CMD_SYNCPOINT_TYPE_FENCE 1 - -/* --- Memory allocation flags --- */ - -/* General allocation hints */ -#define KGSL_MEMFLAGS_SECURE 0x00000008ULL -#define KGSL_MEMFLAGS_GPUREADONLY 0x01000000U -#define KGSL_MEMFLAGS_GPUWRITEONLY 0x02000000U -#define KGSL_MEMFLAGS_FORCE_32BIT 0x100000000ULL - -/* Memory caching hints */ -#define KGSL_CACHEMODE_MASK 0x0C000000U -#define KGSL_CACHEMODE_SHIFT 26 - -#define KGSL_CACHEMODE_WRITECOMBINE 0 -#define KGSL_CACHEMODE_UNCACHED 1 -#define KGSL_CACHEMODE_WRITETHROUGH 2 -#define KGSL_CACHEMODE_WRITEBACK 3 - -#define KGSL_MEMFLAGS_USE_CPU_MAP 0x10000000ULL - -/* Memory types for which allocations are made */ -#define KGSL_MEMTYPE_MASK 0x0000FF00 -#define KGSL_MEMTYPE_SHIFT 8 - -#define KGSL_MEMTYPE_OBJECTANY 0 -#define KGSL_MEMTYPE_FRAMEBUFFER 1 -#define KGSL_MEMTYPE_RENDERBUFFER 2 -#define KGSL_MEMTYPE_ARRAYBUFFER 3 -#define KGSL_MEMTYPE_ELEMENTARRAYBUFFER 4 -#define KGSL_MEMTYPE_VERTEXARRAYBUFFER 5 -#define KGSL_MEMTYPE_TEXTURE 6 -#define KGSL_MEMTYPE_SURFACE 7 -#define KGSL_MEMTYPE_EGL_SURFACE 8 -#define KGSL_MEMTYPE_GL 9 -#define KGSL_MEMTYPE_CL 10 -#define KGSL_MEMTYPE_CL_BUFFER_MAP 11 -#define KGSL_MEMTYPE_CL_BUFFER_NOMAP 12 -#define KGSL_MEMTYPE_CL_IMAGE_MAP 13 -#define KGSL_MEMTYPE_CL_IMAGE_NOMAP 14 -#define KGSL_MEMTYPE_CL_KERNEL_STACK 15 -#define KGSL_MEMTYPE_COMMAND 16 -#define KGSL_MEMTYPE_2D 17 -#define KGSL_MEMTYPE_EGL_IMAGE 18 -#define KGSL_MEMTYPE_EGL_SHADOW 19 -#define KGSL_MEMTYPE_MULTISAMPLE 20 -#define KGSL_MEMTYPE_KERNEL 255 - -/* - * Alignment hint, passed as the power of 2 exponent. - * i.e 4k (2^12) would be 12, 64k (2^16)would be 16. - */ -#define KGSL_MEMALIGN_MASK 0x00FF0000 -#define KGSL_MEMALIGN_SHIFT 16 - -enum kgsl_user_mem_type { - KGSL_USER_MEM_TYPE_PMEM = 0x00000000, - KGSL_USER_MEM_TYPE_ASHMEM = 0x00000001, - KGSL_USER_MEM_TYPE_ADDR = 0x00000002, - KGSL_USER_MEM_TYPE_ION = 0x00000003, - /* - * ION type is retained for backwards compatibilty but Ion buffers are - * dma-bufs so try to use that naming if we can - */ - KGSL_USER_MEM_TYPE_DMABUF = 0x00000003, - KGSL_USER_MEM_TYPE_MAX = 0x00000007, -}; -#define KGSL_MEMFLAGS_USERMEM_MASK 0x000000e0 -#define KGSL_MEMFLAGS_USERMEM_SHIFT 5 - -/* - * Unfortunately, enum kgsl_user_mem_type starts at 0 which does not - * leave a good value for allocated memory. In the flags we use - * 0 to indicate allocated memory and thus need to add 1 to the enum - * values. - */ -#define KGSL_USERMEM_FLAG(x) (((x) + 1) << KGSL_MEMFLAGS_USERMEM_SHIFT) - -#define KGSL_MEMFLAGS_NOT_USERMEM 0 -#define KGSL_MEMFLAGS_USERMEM_PMEM KGSL_USERMEM_FLAG(KGSL_USER_MEM_TYPE_PMEM) -#define KGSL_MEMFLAGS_USERMEM_ASHMEM \ - KGSL_USERMEM_FLAG(KGSL_USER_MEM_TYPE_ASHMEM) -#define KGSL_MEMFLAGS_USERMEM_ADDR KGSL_USERMEM_FLAG(KGSL_USER_MEM_TYPE_ADDR) -#define KGSL_MEMFLAGS_USERMEM_ION KGSL_USERMEM_FLAG(KGSL_USER_MEM_TYPE_ION) - -/* --- generic KGSL flag values --- */ - -#define KGSL_FLAGS_NORMALMODE 0x00000000 -#define KGSL_FLAGS_SAFEMODE 0x00000001 -#define KGSL_FLAGS_INITIALIZED0 0x00000002 -#define KGSL_FLAGS_INITIALIZED 0x00000004 -#define KGSL_FLAGS_STARTED 0x00000008 -#define KGSL_FLAGS_ACTIVE 0x00000010 -#define KGSL_FLAGS_RESERVED0 0x00000020 -#define KGSL_FLAGS_RESERVED1 0x00000040 -#define KGSL_FLAGS_RESERVED2 0x00000080 -#define KGSL_FLAGS_SOFT_RESET 0x00000100 -#define KGSL_FLAGS_PER_CONTEXT_TIMESTAMPS 0x00000200 - -/* Server Side Sync Timeout in milliseconds */ -#define KGSL_SYNCOBJ_SERVER_TIMEOUT 2000 - -/* - * Reset status values for context - */ -enum kgsl_ctx_reset_stat { - KGSL_CTX_STAT_NO_ERROR = 0x00000000, - KGSL_CTX_STAT_GUILTY_CONTEXT_RESET_EXT = 0x00000001, - KGSL_CTX_STAT_INNOCENT_CONTEXT_RESET_EXT = 0x00000002, - KGSL_CTX_STAT_UNKNOWN_CONTEXT_RESET_EXT = 0x00000003 -}; - -#define KGSL_CONVERT_TO_MBPS(val) \ - (val*1000*1000U) - -/* device id */ -enum kgsl_deviceid { - KGSL_DEVICE_3D0 = 0x00000000, - KGSL_DEVICE_MAX -}; - -struct kgsl_devinfo { - - unsigned int device_id; - /* chip revision id - * coreid:8 majorrev:8 minorrev:8 patch:8 - */ - unsigned int chip_id; - unsigned int mmu_enabled; - unsigned long gmem_gpubaseaddr; - /* - * This field contains the adreno revision - * number 200, 205, 220, etc... - */ - unsigned int gpu_id; - size_t gmem_sizebytes; -}; - -/* - * struct kgsl_devmemstore - this structure defines the region of memory - * that can be mmap()ed from this driver. The timestamp fields are volatile - * because they are written by the GPU - * @soptimestamp: Start of pipeline timestamp written by GPU before the - * commands in concern are processed - * @sbz: Unused, kept for 8 byte alignment - * @eoptimestamp: End of pipeline timestamp written by GPU after the - * commands in concern are processed - * @sbz2: Unused, kept for 8 byte alignment - * @preempted: Indicates if the context was preempted - * @sbz3: Unused, kept for 8 byte alignment - * @ref_wait_ts: Timestamp on which to generate interrupt, unused now. - * @sbz4: Unused, kept for 8 byte alignment - * @current_context: The current context the GPU is working on - * @sbz5: Unused, kept for 8 byte alignment - */ -struct kgsl_devmemstore { - volatile unsigned int soptimestamp; - unsigned int sbz; - volatile unsigned int eoptimestamp; - unsigned int sbz2; - volatile unsigned int preempted; - unsigned int sbz3; - volatile unsigned int ref_wait_ts; - unsigned int sbz4; - unsigned int current_context; - unsigned int sbz5; -}; - -#define KGSL_MEMSTORE_OFFSET(ctxt_id, field) \ - ((ctxt_id)*sizeof(struct kgsl_devmemstore) + \ - offsetof(struct kgsl_devmemstore, field)) - -/* timestamp id*/ -enum kgsl_timestamp_type { - KGSL_TIMESTAMP_CONSUMED = 0x00000001, /* start-of-pipeline timestamp */ - KGSL_TIMESTAMP_RETIRED = 0x00000002, /* end-of-pipeline timestamp*/ - KGSL_TIMESTAMP_QUEUED = 0x00000003, -}; - -/* property types - used with kgsl_device_getproperty */ -#define KGSL_PROP_DEVICE_INFO 0x1 -#define KGSL_PROP_DEVICE_SHADOW 0x2 -#define KGSL_PROP_DEVICE_POWER 0x3 -#define KGSL_PROP_SHMEM 0x4 -#define KGSL_PROP_SHMEM_APERTURES 0x5 -#define KGSL_PROP_MMU_ENABLE 0x6 -#define KGSL_PROP_INTERRUPT_WAITS 0x7 -#define KGSL_PROP_VERSION 0x8 -#define KGSL_PROP_GPU_RESET_STAT 0x9 -#define KGSL_PROP_PWRCTRL 0xE -#define KGSL_PROP_PWR_CONSTRAINT 0x12 -#define KGSL_PROP_UCHE_GMEM_VADDR 0x13 -#define KGSL_PROP_SP_GENERIC_MEM 0x14 -#define KGSL_PROP_UCODE_VERSION 0x15 -#define KGSL_PROP_GPMU_VERSION 0x16 -#define KGSL_PROP_DEVICE_BITNESS 0x18 - -struct kgsl_shadowprop { - unsigned long gpuaddr; - size_t size; - unsigned int flags; /* contains KGSL_FLAGS_ values */ -}; - -struct kgsl_version { - unsigned int drv_major; - unsigned int drv_minor; - unsigned int dev_major; - unsigned int dev_minor; -}; - -struct kgsl_sp_generic_mem { - uint64_t local; - uint64_t pvt; -}; - -struct kgsl_ucode_version { - unsigned int pfp; - unsigned int pm4; -}; - -struct kgsl_gpmu_version { - unsigned int major; - unsigned int minor; - unsigned int features; -}; - -/* Performance counter groups */ - -#define KGSL_PERFCOUNTER_GROUP_CP 0x0 -#define KGSL_PERFCOUNTER_GROUP_RBBM 0x1 -#define KGSL_PERFCOUNTER_GROUP_PC 0x2 -#define KGSL_PERFCOUNTER_GROUP_VFD 0x3 -#define KGSL_PERFCOUNTER_GROUP_HLSQ 0x4 -#define KGSL_PERFCOUNTER_GROUP_VPC 0x5 -#define KGSL_PERFCOUNTER_GROUP_TSE 0x6 -#define KGSL_PERFCOUNTER_GROUP_RAS 0x7 -#define KGSL_PERFCOUNTER_GROUP_UCHE 0x8 -#define KGSL_PERFCOUNTER_GROUP_TP 0x9 -#define KGSL_PERFCOUNTER_GROUP_SP 0xA -#define KGSL_PERFCOUNTER_GROUP_RB 0xB -#define KGSL_PERFCOUNTER_GROUP_PWR 0xC -#define KGSL_PERFCOUNTER_GROUP_VBIF 0xD -#define KGSL_PERFCOUNTER_GROUP_VBIF_PWR 0xE -#define KGSL_PERFCOUNTER_GROUP_MH 0xF -#define KGSL_PERFCOUNTER_GROUP_PA_SU 0x10 -#define KGSL_PERFCOUNTER_GROUP_SQ 0x11 -#define KGSL_PERFCOUNTER_GROUP_SX 0x12 -#define KGSL_PERFCOUNTER_GROUP_TCF 0x13 -#define KGSL_PERFCOUNTER_GROUP_TCM 0x14 -#define KGSL_PERFCOUNTER_GROUP_TCR 0x15 -#define KGSL_PERFCOUNTER_GROUP_L2 0x16 -#define KGSL_PERFCOUNTER_GROUP_VSC 0x17 -#define KGSL_PERFCOUNTER_GROUP_CCU 0x18 -#define KGSL_PERFCOUNTER_GROUP_LRZ 0x19 -#define KGSL_PERFCOUNTER_GROUP_CMP 0x1A -#define KGSL_PERFCOUNTER_GROUP_ALWAYSON 0x1B -#define KGSL_PERFCOUNTER_GROUP_SP_PWR 0x1C -#define KGSL_PERFCOUNTER_GROUP_TP_PWR 0x1D -#define KGSL_PERFCOUNTER_GROUP_RB_PWR 0x1E -#define KGSL_PERFCOUNTER_GROUP_CCU_PWR 0x1F -#define KGSL_PERFCOUNTER_GROUP_UCHE_PWR 0x20 -#define KGSL_PERFCOUNTER_GROUP_CP_PWR 0x21 -#define KGSL_PERFCOUNTER_GROUP_GPMU_PWR 0x22 -#define KGSL_PERFCOUNTER_GROUP_ALWAYSON_PWR 0x23 -#define KGSL_PERFCOUNTER_GROUP_MAX 0x24 - -#define KGSL_PERFCOUNTER_NOT_USED 0xFFFFFFFF -#define KGSL_PERFCOUNTER_BROKEN 0xFFFFFFFE - -/* structure holds list of ibs */ -struct kgsl_ibdesc { - unsigned long gpuaddr; - unsigned long __pad; - size_t sizedwords; - unsigned int ctrl; -}; - -/** - * struct kgsl_cmdbatch_profiling_buffer - * @wall_clock_s: Ringbuffer submission time (seconds). - * If KGSL_CMDBATCH_PROFILING_KTIME is set, time is provided - * in kernel clocks, otherwise wall clock time is used. - * @wall_clock_ns: Ringbuffer submission time (nanoseconds). - * If KGSL_CMDBATCH_PROFILING_KTIME is set time is provided - * in kernel clocks, otherwise wall clock time is used. - * @gpu_ticks_queued: GPU ticks at ringbuffer submission - * @gpu_ticks_submitted: GPU ticks when starting cmdbatch execution - * @gpu_ticks_retired: GPU ticks when finishing cmdbatch execution - * - * This structure defines the profiling buffer used to measure cmdbatch - * execution time - */ -struct kgsl_cmdbatch_profiling_buffer { - uint64_t wall_clock_s; - uint64_t wall_clock_ns; - uint64_t gpu_ticks_queued; - uint64_t gpu_ticks_submitted; - uint64_t gpu_ticks_retired; -}; - -/* ioctls */ -#define KGSL_IOC_TYPE 0x09 - -/* get misc info about the GPU - type should be a value from enum kgsl_property_type - value points to a structure that varies based on type - sizebytes is sizeof() that structure - for KGSL_PROP_DEVICE_INFO, use struct kgsl_devinfo - this structure contaings hardware versioning info. - for KGSL_PROP_DEVICE_SHADOW, use struct kgsl_shadowprop - this is used to find mmap() offset and sizes for mapping - struct kgsl_memstore into userspace. -*/ -struct kgsl_device_getproperty { - unsigned int type; - void __user *value; - size_t sizebytes; -}; - -#define IOCTL_KGSL_DEVICE_GETPROPERTY \ - _IOWR(KGSL_IOC_TYPE, 0x2, struct kgsl_device_getproperty) - -/* IOCTL_KGSL_DEVICE_READ (0x3) - removed 03/2012 - */ - -/* block until the GPU has executed past a given timestamp - * timeout is in milliseconds. - */ -struct kgsl_device_waittimestamp { - unsigned int timestamp; - unsigned int timeout; -}; - -#define IOCTL_KGSL_DEVICE_WAITTIMESTAMP \ - _IOW(KGSL_IOC_TYPE, 0x6, struct kgsl_device_waittimestamp) - -struct kgsl_device_waittimestamp_ctxtid { - unsigned int context_id; - unsigned int timestamp; - unsigned int timeout; -}; - -#define IOCTL_KGSL_DEVICE_WAITTIMESTAMP_CTXTID \ - _IOW(KGSL_IOC_TYPE, 0x7, struct kgsl_device_waittimestamp_ctxtid) - -/* DEPRECATED: issue indirect commands to the GPU. - * drawctxt_id must have been created with IOCTL_KGSL_DRAWCTXT_CREATE - * ibaddr and sizedwords must specify a subset of a buffer created - * with IOCTL_KGSL_SHAREDMEM_FROM_PMEM - * flags may be a mask of KGSL_CONTEXT_ values - * timestamp is a returned counter value which can be passed to - * other ioctls to determine when the commands have been executed by - * the GPU. - * - * This fucntion is deprecated - consider using IOCTL_KGSL_SUBMIT_COMMANDS - * instead - */ -struct kgsl_ringbuffer_issueibcmds { - unsigned int drawctxt_id; - unsigned long ibdesc_addr; - unsigned int numibs; - unsigned int timestamp; /*output param */ - unsigned int flags; -}; - -#define IOCTL_KGSL_RINGBUFFER_ISSUEIBCMDS \ - _IOWR(KGSL_IOC_TYPE, 0x10, struct kgsl_ringbuffer_issueibcmds) - -/* read the most recently executed timestamp value - * type should be a value from enum kgsl_timestamp_type - */ -struct kgsl_cmdstream_readtimestamp { - unsigned int type; - unsigned int timestamp; /*output param */ -}; - -#define IOCTL_KGSL_CMDSTREAM_READTIMESTAMP_OLD \ - _IOR(KGSL_IOC_TYPE, 0x11, struct kgsl_cmdstream_readtimestamp) - -#define IOCTL_KGSL_CMDSTREAM_READTIMESTAMP \ - _IOWR(KGSL_IOC_TYPE, 0x11, struct kgsl_cmdstream_readtimestamp) - -/* free memory when the GPU reaches a given timestamp. - * gpuaddr specify a memory region created by a - * IOCTL_KGSL_SHAREDMEM_FROM_PMEM call - * type should be a value from enum kgsl_timestamp_type - */ -struct kgsl_cmdstream_freememontimestamp { - unsigned long gpuaddr; - unsigned int type; - unsigned int timestamp; -}; - -#define IOCTL_KGSL_CMDSTREAM_FREEMEMONTIMESTAMP \ - _IOW(KGSL_IOC_TYPE, 0x12, struct kgsl_cmdstream_freememontimestamp) - -/* Previous versions of this header had incorrectly defined - IOCTL_KGSL_CMDSTREAM_FREEMEMONTIMESTAMP as a read-only ioctl instead - of a write only ioctl. To ensure binary compatability, the following - #define will be used to intercept the incorrect ioctl -*/ - -#define IOCTL_KGSL_CMDSTREAM_FREEMEMONTIMESTAMP_OLD \ - _IOR(KGSL_IOC_TYPE, 0x12, struct kgsl_cmdstream_freememontimestamp) - -/* create a draw context, which is used to preserve GPU state. - * The flags field may contain a mask KGSL_CONTEXT_* values - */ -struct kgsl_drawctxt_create { - unsigned int flags; - unsigned int drawctxt_id; /*output param */ -}; - -#define IOCTL_KGSL_DRAWCTXT_CREATE \ - _IOWR(KGSL_IOC_TYPE, 0x13, struct kgsl_drawctxt_create) - -/* destroy a draw context */ -struct kgsl_drawctxt_destroy { - unsigned int drawctxt_id; -}; - -#define IOCTL_KGSL_DRAWCTXT_DESTROY \ - _IOW(KGSL_IOC_TYPE, 0x14, struct kgsl_drawctxt_destroy) - -/* add a block of pmem, fb, ashmem or user allocated address - * into the GPU address space */ -struct kgsl_map_user_mem { - int fd; - unsigned long gpuaddr; /*output param */ - size_t len; - size_t offset; - unsigned long hostptr; /*input param */ - enum kgsl_user_mem_type memtype; - unsigned int flags; -}; - -#define IOCTL_KGSL_MAP_USER_MEM \ - _IOWR(KGSL_IOC_TYPE, 0x15, struct kgsl_map_user_mem) - -struct kgsl_cmdstream_readtimestamp_ctxtid { - unsigned int context_id; - unsigned int type; - unsigned int timestamp; /*output param */ -}; - -#define IOCTL_KGSL_CMDSTREAM_READTIMESTAMP_CTXTID \ - _IOWR(KGSL_IOC_TYPE, 0x16, struct kgsl_cmdstream_readtimestamp_ctxtid) - -struct kgsl_cmdstream_freememontimestamp_ctxtid { - unsigned int context_id; - unsigned long gpuaddr; - unsigned int type; - unsigned int timestamp; -}; - -#define IOCTL_KGSL_CMDSTREAM_FREEMEMONTIMESTAMP_CTXTID \ - _IOW(KGSL_IOC_TYPE, 0x17, \ - struct kgsl_cmdstream_freememontimestamp_ctxtid) - -/* add a block of pmem or fb into the GPU address space */ -struct kgsl_sharedmem_from_pmem { - int pmem_fd; - unsigned long gpuaddr; /*output param */ - unsigned int len; - unsigned int offset; -}; - -#define IOCTL_KGSL_SHAREDMEM_FROM_PMEM \ - _IOWR(KGSL_IOC_TYPE, 0x20, struct kgsl_sharedmem_from_pmem) - -/* remove memory from the GPU's address space */ -struct kgsl_sharedmem_free { - unsigned long gpuaddr; -}; - -#define IOCTL_KGSL_SHAREDMEM_FREE \ - _IOW(KGSL_IOC_TYPE, 0x21, struct kgsl_sharedmem_free) - -struct kgsl_cff_user_event { - unsigned char cff_opcode; - unsigned int op1; - unsigned int op2; - unsigned int op3; - unsigned int op4; - unsigned int op5; - unsigned int __pad[2]; -}; - -#define IOCTL_KGSL_CFF_USER_EVENT \ - _IOW(KGSL_IOC_TYPE, 0x31, struct kgsl_cff_user_event) - -struct kgsl_gmem_desc { - unsigned int x; - unsigned int y; - unsigned int width; - unsigned int height; - unsigned int pitch; -}; - -struct kgsl_buffer_desc { - void *hostptr; - unsigned long gpuaddr; - int size; - unsigned int format; - unsigned int pitch; - unsigned int enabled; -}; - -struct kgsl_bind_gmem_shadow { - unsigned int drawctxt_id; - struct kgsl_gmem_desc gmem_desc; - unsigned int shadow_x; - unsigned int shadow_y; - struct kgsl_buffer_desc shadow_buffer; - unsigned int buffer_id; -}; - -#define IOCTL_KGSL_DRAWCTXT_BIND_GMEM_SHADOW \ - _IOW(KGSL_IOC_TYPE, 0x22, struct kgsl_bind_gmem_shadow) - -/* add a block of memory into the GPU address space */ - -/* - * IOCTL_KGSL_SHAREDMEM_FROM_VMALLOC deprecated 09/2012 - * use IOCTL_KGSL_GPUMEM_ALLOC instead - */ - -struct kgsl_sharedmem_from_vmalloc { - unsigned long gpuaddr; /*output param */ - unsigned int hostptr; - unsigned int flags; -}; - -#define IOCTL_KGSL_SHAREDMEM_FROM_VMALLOC \ - _IOWR(KGSL_IOC_TYPE, 0x23, struct kgsl_sharedmem_from_vmalloc) - -/* - * This is being deprecated in favor of IOCTL_KGSL_GPUMEM_CACHE_SYNC which - * supports both directions (flush and invalidate). This code will still - * work, but by definition it will do a flush of the cache which might not be - * what you want to have happen on a buffer following a GPU operation. It is - * safer to go with IOCTL_KGSL_GPUMEM_CACHE_SYNC - */ - -#define IOCTL_KGSL_SHAREDMEM_FLUSH_CACHE \ - _IOW(KGSL_IOC_TYPE, 0x24, struct kgsl_sharedmem_free) - -struct kgsl_drawctxt_set_bin_base_offset { - unsigned int drawctxt_id; - unsigned int offset; -}; - -#define IOCTL_KGSL_DRAWCTXT_SET_BIN_BASE_OFFSET \ - _IOW(KGSL_IOC_TYPE, 0x25, struct kgsl_drawctxt_set_bin_base_offset) - -enum kgsl_cmdwindow_type { - KGSL_CMDWINDOW_MIN = 0x00000000, - KGSL_CMDWINDOW_2D = 0x00000000, - KGSL_CMDWINDOW_3D = 0x00000001, /* legacy */ - KGSL_CMDWINDOW_MMU = 0x00000002, - KGSL_CMDWINDOW_ARBITER = 0x000000FF, - KGSL_CMDWINDOW_MAX = 0x000000FF, -}; - -/* write to the command window */ -struct kgsl_cmdwindow_write { - enum kgsl_cmdwindow_type target; - unsigned int addr; - unsigned int data; -}; - -#define IOCTL_KGSL_CMDWINDOW_WRITE \ - _IOW(KGSL_IOC_TYPE, 0x2e, struct kgsl_cmdwindow_write) - -struct kgsl_gpumem_alloc { - unsigned long gpuaddr; /* output param */ - size_t size; - unsigned int flags; -}; - -#define IOCTL_KGSL_GPUMEM_ALLOC \ - _IOWR(KGSL_IOC_TYPE, 0x2f, struct kgsl_gpumem_alloc) - -struct kgsl_cff_syncmem { - unsigned long gpuaddr; - size_t len; - unsigned int __pad[2]; /* For future binary compatibility */ -}; - -#define IOCTL_KGSL_CFF_SYNCMEM \ - _IOW(KGSL_IOC_TYPE, 0x30, struct kgsl_cff_syncmem) - -/* - * A timestamp event allows the user space to register an action following an - * expired timestamp. Note IOCTL_KGSL_TIMESTAMP_EVENT has been redefined to - * _IOWR to support fences which need to return a fd for the priv parameter. - */ - -struct kgsl_timestamp_event { - int type; /* Type of event (see list below) */ - unsigned int timestamp; /* Timestamp to trigger event on */ - unsigned int context_id; /* Context for the timestamp */ - void __user *priv; /* Pointer to the event specific blob */ - size_t len; /* Size of the event specific blob */ -}; - -#define IOCTL_KGSL_TIMESTAMP_EVENT_OLD \ - _IOW(KGSL_IOC_TYPE, 0x31, struct kgsl_timestamp_event) - -/* A genlock timestamp event releases an existing lock on timestamp expire */ - -#define KGSL_TIMESTAMP_EVENT_GENLOCK 1 - -struct kgsl_timestamp_event_genlock { - int handle; /* Handle of the genlock lock to release */ -}; - -/* A fence timestamp event releases an existing lock on timestamp expire */ - -#define KGSL_TIMESTAMP_EVENT_FENCE 2 - -struct kgsl_timestamp_event_fence { - int fence_fd; /* Fence to signal */ -}; - -/* - * Set a property within the kernel. Uses the same structure as - * IOCTL_KGSL_GETPROPERTY - */ - -#define IOCTL_KGSL_SETPROPERTY \ - _IOW(KGSL_IOC_TYPE, 0x32, struct kgsl_device_getproperty) - -#define IOCTL_KGSL_TIMESTAMP_EVENT \ - _IOWR(KGSL_IOC_TYPE, 0x33, struct kgsl_timestamp_event) - -/** - * struct kgsl_gpumem_alloc_id - argument to IOCTL_KGSL_GPUMEM_ALLOC_ID - * @id: returned id value for this allocation. - * @flags: mask of KGSL_MEM* values requested and actual flags on return. - * @size: requested size of the allocation and actual size on return. - * @mmapsize: returned size to pass to mmap() which may be larger than 'size' - * @gpuaddr: returned GPU address for the allocation - * - * Allocate memory for access by the GPU. The flags and size fields are echoed - * back by the kernel, so that the caller can know if the request was - * adjusted. - * - * Supported flags: - * KGSL_MEMFLAGS_GPUREADONLY: the GPU will be unable to write to the buffer - * KGSL_MEMTYPE*: usage hint for debugging aid - * KGSL_MEMALIGN*: alignment hint, may be ignored or adjusted by the kernel. - * KGSL_MEMFLAGS_USE_CPU_MAP: If set on call and return, the returned GPU - * address will be 0. Calling mmap() will set the GPU address. - */ -struct kgsl_gpumem_alloc_id { - unsigned int id; - unsigned int flags; - size_t size; - size_t mmapsize; - unsigned long gpuaddr; -/* private: reserved for future use*/ - unsigned long __pad[2]; -}; - -#define IOCTL_KGSL_GPUMEM_ALLOC_ID \ - _IOWR(KGSL_IOC_TYPE, 0x34, struct kgsl_gpumem_alloc_id) - -/** - * struct kgsl_gpumem_free_id - argument to IOCTL_KGSL_GPUMEM_FREE_ID - * @id: GPU allocation id to free - * - * Free an allocation by id, in case a GPU address has not been assigned or - * is unknown. Freeing an allocation by id with this ioctl or by GPU address - * with IOCTL_KGSL_SHAREDMEM_FREE are equivalent. - */ -struct kgsl_gpumem_free_id { - unsigned int id; -/* private: reserved for future use*/ - unsigned int __pad; -}; - -#define IOCTL_KGSL_GPUMEM_FREE_ID \ - _IOWR(KGSL_IOC_TYPE, 0x35, struct kgsl_gpumem_free_id) - -/** - * struct kgsl_gpumem_get_info - argument to IOCTL_KGSL_GPUMEM_GET_INFO - * @gpuaddr: GPU address to query. Also set on return. - * @id: GPU allocation id to query. Also set on return. - * @flags: returned mask of KGSL_MEM* values. - * @size: returned size of the allocation. - * @mmapsize: returned size to pass mmap(), which may be larger than 'size' - * @useraddr: returned address of the userspace mapping for this buffer - * - * This ioctl allows querying of all user visible attributes of an existing - * allocation, by either the GPU address or the id returned by a previous - * call to IOCTL_KGSL_GPUMEM_ALLOC_ID. Legacy allocation ioctls may not - * return all attributes so this ioctl can be used to look them up if needed. - * - */ -struct kgsl_gpumem_get_info { - unsigned long gpuaddr; - unsigned int id; - unsigned int flags; - size_t size; - size_t mmapsize; - unsigned long useraddr; -/* private: reserved for future use*/ - unsigned long __pad[4]; -}; - -#define IOCTL_KGSL_GPUMEM_GET_INFO\ - _IOWR(KGSL_IOC_TYPE, 0x36, struct kgsl_gpumem_get_info) - -/** - * struct kgsl_gpumem_sync_cache - argument to IOCTL_KGSL_GPUMEM_SYNC_CACHE - * @gpuaddr: GPU address of the buffer to sync. - * @id: id of the buffer to sync. Either gpuaddr or id is sufficient. - * @op: a mask of KGSL_GPUMEM_CACHE_* values - * @offset: offset into the buffer - * @length: number of bytes starting from offset to perform - * the cache operation on - * - * Sync the L2 cache for memory headed to and from the GPU - this replaces - * KGSL_SHAREDMEM_FLUSH_CACHE since it can handle cache management for both - * directions - * - */ -struct kgsl_gpumem_sync_cache { - unsigned long gpuaddr; - unsigned int id; - unsigned int op; - size_t offset; - size_t length; -}; - -#define KGSL_GPUMEM_CACHE_CLEAN (1 << 0) -#define KGSL_GPUMEM_CACHE_TO_GPU KGSL_GPUMEM_CACHE_CLEAN - -#define KGSL_GPUMEM_CACHE_INV (1 << 1) -#define KGSL_GPUMEM_CACHE_FROM_GPU KGSL_GPUMEM_CACHE_INV - -#define KGSL_GPUMEM_CACHE_FLUSH \ - (KGSL_GPUMEM_CACHE_CLEAN | KGSL_GPUMEM_CACHE_INV) - -/* Flag to ensure backwards compatibility of kgsl_gpumem_sync_cache struct */ -#define KGSL_GPUMEM_CACHE_RANGE (1 << 31U) - -#define IOCTL_KGSL_GPUMEM_SYNC_CACHE \ - _IOW(KGSL_IOC_TYPE, 0x37, struct kgsl_gpumem_sync_cache) - -/** - * struct kgsl_perfcounter_get - argument to IOCTL_KGSL_PERFCOUNTER_GET - * @groupid: Performance counter group ID - * @countable: Countable to select within the group - * @offset: Return offset of the reserved LO counter - * @offset_hi: Return offset of the reserved HI counter - * - * Get an available performance counter from a specified groupid. The offset - * of the performance counter will be returned after successfully assigning - * the countable to the counter for the specified group. An error will be - * returned and an offset of 0 if the groupid is invalid or there are no - * more counters left. After successfully getting a perfcounter, the user - * must call kgsl_perfcounter_put(groupid, contable) when finished with - * the perfcounter to clear up perfcounter resources. - * - */ -struct kgsl_perfcounter_get { - unsigned int groupid; - unsigned int countable; - unsigned int offset; - unsigned int offset_hi; -/* private: reserved for future use */ - unsigned int __pad; /* For future binary compatibility */ -}; - -#define IOCTL_KGSL_PERFCOUNTER_GET \ - _IOWR(KGSL_IOC_TYPE, 0x38, struct kgsl_perfcounter_get) - -/** - * struct kgsl_perfcounter_put - argument to IOCTL_KGSL_PERFCOUNTER_PUT - * @groupid: Performance counter group ID - * @countable: Countable to release within the group - * - * Put an allocated performance counter to allow others to have access to the - * resource that was previously taken. This is only to be called after - * successfully getting a performance counter from kgsl_perfcounter_get(). - * - */ -struct kgsl_perfcounter_put { - unsigned int groupid; - unsigned int countable; -/* private: reserved for future use */ - unsigned int __pad[2]; /* For future binary compatibility */ -}; - -#define IOCTL_KGSL_PERFCOUNTER_PUT \ - _IOW(KGSL_IOC_TYPE, 0x39, struct kgsl_perfcounter_put) - -/** - * struct kgsl_perfcounter_query - argument to IOCTL_KGSL_PERFCOUNTER_QUERY - * @groupid: Performance counter group ID - * @countable: Return active countables array - * @size: Size of active countables array - * @max_counters: Return total number counters for the group ID - * - * Query the available performance counters given a groupid. The array - * *countables is used to return the current active countables in counters. - * The size of the array is passed in so the kernel will only write at most - * size or counter->size for the group id. The total number of available - * counters for the group ID is returned in max_counters. - * If the array or size passed in are invalid, then only the maximum number - * of counters will be returned, no data will be written to *countables. - * If the groupid is invalid an error code will be returned. - * - */ -struct kgsl_perfcounter_query { - unsigned int groupid; - /* Array to return the current countable for up to size counters */ - unsigned int __user *countables; - unsigned int count; - unsigned int max_counters; -/* private: reserved for future use */ - unsigned int __pad[2]; /* For future binary compatibility */ -}; - -#define IOCTL_KGSL_PERFCOUNTER_QUERY \ - _IOWR(KGSL_IOC_TYPE, 0x3A, struct kgsl_perfcounter_query) - -/** - * struct kgsl_perfcounter_query - argument to IOCTL_KGSL_PERFCOUNTER_QUERY - * @groupid: Performance counter group IDs - * @countable: Performance counter countable IDs - * @value: Return performance counter reads - * @size: Size of all arrays (groupid/countable pair and return value) - * - * Read in the current value of a performance counter given by the groupid - * and countable. - * - */ - -struct kgsl_perfcounter_read_group { - unsigned int groupid; - unsigned int countable; - unsigned long long value; -}; - -struct kgsl_perfcounter_read { - struct kgsl_perfcounter_read_group __user *reads; - unsigned int count; -/* private: reserved for future use */ - unsigned int __pad[2]; /* For future binary compatibility */ -}; - -#define IOCTL_KGSL_PERFCOUNTER_READ \ - _IOWR(KGSL_IOC_TYPE, 0x3B, struct kgsl_perfcounter_read) -/* - * struct kgsl_gpumem_sync_cache_bulk - argument to - * IOCTL_KGSL_GPUMEM_SYNC_CACHE_BULK - * @id_list: list of GPU buffer ids of the buffers to sync - * @count: number of GPU buffer ids in id_list - * @op: a mask of KGSL_GPUMEM_CACHE_* values - * - * Sync the cache for memory headed to and from the GPU. Certain - * optimizations can be made on the cache operation based on the total - * size of the working set of memory to be managed. - */ -struct kgsl_gpumem_sync_cache_bulk { - unsigned int __user *id_list; - unsigned int count; - unsigned int op; -/* private: reserved for future use */ - unsigned int __pad[2]; /* For future binary compatibility */ -}; - -#define IOCTL_KGSL_GPUMEM_SYNC_CACHE_BULK \ - _IOWR(KGSL_IOC_TYPE, 0x3C, struct kgsl_gpumem_sync_cache_bulk) - -/* - * struct kgsl_cmd_syncpoint_timestamp - * @context_id: ID of a KGSL context - * @timestamp: GPU timestamp - * - * This structure defines a syncpoint comprising a context/timestamp pair. A - * list of these may be passed by IOCTL_KGSL_SUBMIT_COMMANDS to define - * dependencies that must be met before the command can be submitted to the - * hardware - */ -struct kgsl_cmd_syncpoint_timestamp { - unsigned int context_id; - unsigned int timestamp; -}; - -struct kgsl_cmd_syncpoint_fence { - int fd; -}; - -/** - * struct kgsl_cmd_syncpoint - Define a sync point for a command batch - * @type: type of sync point defined here - * @priv: Pointer to the type specific buffer - * @size: Size of the type specific buffer - * - * This structure contains pointers defining a specific command sync point. - * The pointer and size should point to a type appropriate structure. - */ -struct kgsl_cmd_syncpoint { - int type; - void __user *priv; - size_t size; -}; - -/* Flag to indicate that the cmdlist may contain memlists */ -#define KGSL_IBDESC_MEMLIST 0x1 - -/* Flag to point out the cmdbatch profiling buffer in the memlist */ -#define KGSL_IBDESC_PROFILING_BUFFER 0x2 - -/** - * struct kgsl_submit_commands - Argument to IOCTL_KGSL_SUBMIT_COMMANDS - * @context_id: KGSL context ID that owns the commands - * @flags: - * @cmdlist: User pointer to a list of kgsl_ibdesc structures - * @numcmds: Number of commands listed in cmdlist - * @synclist: User pointer to a list of kgsl_cmd_syncpoint structures - * @numsyncs: Number of sync points listed in synclist - * @timestamp: On entry the a user defined timestamp, on exist the timestamp - * assigned to the command batch - * - * This structure specifies a command to send to the GPU hardware. This is - * similar to kgsl_issueibcmds expect that it doesn't support the legacy way to - * submit IB lists and it adds sync points to block the IB until the - * dependencies are satisified. This entry point is the new and preferred way - * to submit commands to the GPU. The memory list can be used to specify all - * memory that is referrenced in the current set of commands. - */ - -struct kgsl_submit_commands { - unsigned int context_id; - unsigned int flags; - struct kgsl_ibdesc __user *cmdlist; - unsigned int numcmds; - struct kgsl_cmd_syncpoint __user *synclist; - unsigned int numsyncs; - unsigned int timestamp; -/* private: reserved for future use */ - unsigned int __pad[4]; -}; - -#define IOCTL_KGSL_SUBMIT_COMMANDS \ - _IOWR(KGSL_IOC_TYPE, 0x3D, struct kgsl_submit_commands) - -/** - * struct kgsl_device_constraint - device constraint argument - * @context_id: KGSL context ID - * @type: type of constraint i.e pwrlevel/none - * @data: constraint data - * @size: size of the constraint data - */ -struct kgsl_device_constraint { - unsigned int type; - unsigned int context_id; - void __user *data; - size_t size; -}; - -/* Constraint Type*/ -#define KGSL_CONSTRAINT_NONE 0 -#define KGSL_CONSTRAINT_PWRLEVEL 1 - -/* PWRLEVEL constraint level*/ -/* set to min frequency */ -#define KGSL_CONSTRAINT_PWR_MIN 0 -/* set to max frequency */ -#define KGSL_CONSTRAINT_PWR_MAX 1 - -struct kgsl_device_constraint_pwrlevel { - unsigned int level; -}; - -/** - * struct kgsl_syncsource_create - Argument to IOCTL_KGSL_SYNCSOURCE_CREATE - * @id: returned id for the syncsource that was created. - * - * This ioctl creates a userspace sync timeline. - */ - -struct kgsl_syncsource_create { - unsigned int id; -/* private: reserved for future use */ - unsigned int __pad[3]; -}; - -#define IOCTL_KGSL_SYNCSOURCE_CREATE \ - _IOWR(KGSL_IOC_TYPE, 0x40, struct kgsl_syncsource_create) - -/** - * struct kgsl_syncsource_destroy - Argument to IOCTL_KGSL_SYNCSOURCE_DESTROY - * @id: syncsource id to destroy - * - * This ioctl creates a userspace sync timeline. - */ - -struct kgsl_syncsource_destroy { - unsigned int id; -/* private: reserved for future use */ - unsigned int __pad[3]; -}; - -#define IOCTL_KGSL_SYNCSOURCE_DESTROY \ - _IOWR(KGSL_IOC_TYPE, 0x41, struct kgsl_syncsource_destroy) - -/** - * struct kgsl_syncsource_create_fence - Argument to - * IOCTL_KGSL_SYNCSOURCE_CREATE_FENCE - * @id: syncsource id - * @fence_fd: returned sync_fence fd - * - * Create a fence that may be signaled by userspace by calling - * IOCTL_KGSL_SYNCSOURCE_SIGNAL_FENCE. There are no order dependencies between - * these fences. - */ -struct kgsl_syncsource_create_fence { - unsigned int id; - int fence_fd; -/* private: reserved for future use */ - unsigned int __pad[4]; -}; - -/** - * struct kgsl_syncsource_signal_fence - Argument to - * IOCTL_KGSL_SYNCSOURCE_SIGNAL_FENCE - * @id: syncsource id - * @fence_fd: sync_fence fd to signal - * - * Signal a fence that was created by a IOCTL_KGSL_SYNCSOURCE_CREATE_FENCE - * call using the same syncsource id. This allows a fence to be shared - * to other processes but only signaled by the process owning the fd - * used to create the fence. - */ -#define IOCTL_KGSL_SYNCSOURCE_CREATE_FENCE \ - _IOWR(KGSL_IOC_TYPE, 0x42, struct kgsl_syncsource_create_fence) - -struct kgsl_syncsource_signal_fence { - unsigned int id; - int fence_fd; -/* private: reserved for future use */ - unsigned int __pad[4]; -}; - -#define IOCTL_KGSL_SYNCSOURCE_SIGNAL_FENCE \ - _IOWR(KGSL_IOC_TYPE, 0x43, struct kgsl_syncsource_signal_fence) - -/** - * struct kgsl_cff_sync_gpuobj - Argument to IOCTL_KGSL_CFF_SYNC_GPUOBJ - * @offset: Offset into the GPU object to sync - * @length: Number of bytes to sync - * @id: ID of the GPU object to sync - */ -struct kgsl_cff_sync_gpuobj { - uint64_t offset; - uint64_t length; - unsigned int id; -}; - -#define IOCTL_KGSL_CFF_SYNC_GPUOBJ \ - _IOW(KGSL_IOC_TYPE, 0x44, struct kgsl_cff_sync_gpuobj) - -/** - * struct kgsl_gpuobj_alloc - Argument to IOCTL_KGSL_GPUOBJ_ALLOC - * @size: Size in bytes of the object to allocate - * @flags: mask of KGSL_MEMFLAG_* bits - * @va_len: Size in bytes of the virtual region to allocate - * @mmapsize: Returns the mmap() size of the object - * @id: Returns the GPU object ID of the new object - * @metadata_len: Length of the metdata to copy from the user - * @metadata: Pointer to the user specified metadata to store for the object - */ -struct kgsl_gpuobj_alloc { - uint64_t size; - uint64_t flags; - uint64_t va_len; - uint64_t mmapsize; - unsigned int id; - unsigned int metadata_len; - uint64_t metadata; -}; - -/* Let the user know that this header supports the gpuobj metadata */ -#define KGSL_GPUOBJ_ALLOC_METADATA_MAX 64 - -#define IOCTL_KGSL_GPUOBJ_ALLOC \ - _IOWR(KGSL_IOC_TYPE, 0x45, struct kgsl_gpuobj_alloc) - -/** - * struct kgsl_gpuobj_free - Argument to IOCTL_KGLS_GPUOBJ_FREE - * @flags: Mask of: KGSL_GUPOBJ_FREE_ON_EVENT - * @priv: Pointer to the private object if KGSL_GPUOBJ_FREE_ON_EVENT is - * specified - * @id: ID of the GPU object to free - * @type: If KGSL_GPUOBJ_FREE_ON_EVENT is specified, the type of asynchronous - * event to free on - * @len: Length of the data passed in priv - */ -struct kgsl_gpuobj_free { - uint64_t flags; - uint64_t __user priv; - unsigned int id; - unsigned int type; - unsigned int len; -}; - -#define KGSL_GPUOBJ_FREE_ON_EVENT 1 - -#define KGSL_GPU_EVENT_TIMESTAMP 1 -#define KGSL_GPU_EVENT_FENCE 2 - -/** - * struct kgsl_gpu_event_timestamp - Specifies a timestamp event to free a GPU - * object on - * @context_id: ID of the timestamp event to wait for - * @timestamp: Timestamp of the timestamp event to wait for - */ -struct kgsl_gpu_event_timestamp { - unsigned int context_id; - unsigned int timestamp; -}; - -/** - * struct kgsl_gpu_event_fence - Specifies a fence ID to to free a GPU object on - * @fd: File descriptor for the fence - */ -struct kgsl_gpu_event_fence { - int fd; -}; - -#define IOCTL_KGSL_GPUOBJ_FREE \ - _IOW(KGSL_IOC_TYPE, 0x46, struct kgsl_gpuobj_free) - -/** - * struct kgsl_gpuobj_info - argument to IOCTL_KGSL_GPUOBJ_INFO - * @gpuaddr: GPU address of the object - * @flags: Current flags for the object - * @size: Size of the object - * @va_len: VA size of the object - * @va_addr: Virtual address of the object (if it is mapped) - * id - GPU object ID of the object to query - */ -struct kgsl_gpuobj_info { - uint64_t gpuaddr; - uint64_t flags; - uint64_t size; - uint64_t va_len; - uint64_t va_addr; - unsigned int id; -}; - -#define IOCTL_KGSL_GPUOBJ_INFO \ - _IOWR(KGSL_IOC_TYPE, 0x47, struct kgsl_gpuobj_info) - -/** - * struct kgsl_gpuobj_import - argument to IOCTL_KGSL_GPUOBJ_IMPORT - * @priv: Pointer to the private data for the import type - * @priv_len: Length of the private data - * @flags: Mask of KGSL_MEMFLAG_ flags - * @type: Type of the import (KGSL_USER_MEM_TYPE_*) - * @id: Returns the ID of the new GPU object - */ -struct kgsl_gpuobj_import { - uint64_t __user priv; - uint64_t priv_len; - uint64_t flags; - unsigned int type; - unsigned int id; -}; - -/** - * struct kgsl_gpuobj_import_dma_buf - import a dmabuf object - * @fd: File descriptor for the dma-buf object - */ -struct kgsl_gpuobj_import_dma_buf { - int fd; -}; - -/** - * struct kgsl_gpuobj_import_useraddr - import an object based on a useraddr - * @virtaddr: Virtual address of the object to import - */ -struct kgsl_gpuobj_import_useraddr { - uint64_t virtaddr; -}; - -#define IOCTL_KGSL_GPUOBJ_IMPORT \ - _IOWR(KGSL_IOC_TYPE, 0x48, struct kgsl_gpuobj_import) - -/** - * struct kgsl_gpuobj_sync_obj - Individual GPU object to sync - * @offset: Offset within the GPU object to sync - * @length: Number of bytes to sync - * @id: ID of the GPU object to sync - * @op: Cache operation to execute - */ - -struct kgsl_gpuobj_sync_obj { - uint64_t offset; - uint64_t length; - unsigned int id; - unsigned int op; -}; - -/** - * struct kgsl_gpuobj_sync - Argument for IOCTL_KGSL_GPUOBJ_SYNC - * @objs: Pointer to an array of kgsl_gpuobj_sync_obj structs - * @obj_len: Size of each item in the array - * @count: Number of items in the array - */ - -struct kgsl_gpuobj_sync { - uint64_t __user objs; - unsigned int obj_len; - unsigned int count; -}; - -#define IOCTL_KGSL_GPUOBJ_SYNC \ - _IOW(KGSL_IOC_TYPE, 0x49, struct kgsl_gpuobj_sync) - -/** - * struct kgsl_command_object - GPU command object - * @offset: GPU address offset of the object - * @gpuaddr: GPU address of the object - * @size: Size of the object - * @flags: Current flags for the object - * @id - GPU command object ID - */ -struct kgsl_command_object { - uint64_t offset; - uint64_t gpuaddr; - uint64_t size; - unsigned int flags; - unsigned int id; -}; - -/** - * struct kgsl_command_syncpoint - GPU syncpoint object - * @priv: Pointer to the type specific buffer - * @size: Size of the type specific buffer - * @type: type of sync point defined here - */ -struct kgsl_command_syncpoint { - uint64_t __user priv; - uint64_t size; - unsigned int type; -}; - -/** - * struct kgsl_command_object - Argument for IOCTL_KGSL_GPU_COMMAND - * @flags: Current flags for the object - * @cmdlist: List of kgsl_command_objects for submission - * @cmd_size: Size of kgsl_command_objects structure - * @numcmds: Number of kgsl_command_objects in command list - * @objlist: List of kgsl_command_objects for tracking - * @obj_size: Size of kgsl_command_objects structure - * @numobjs: Number of kgsl_command_objects in object list - * @synclist: List of kgsl_command_syncpoints - * @sync_size: Size of kgsl_command_syncpoint structure - * @numsyncs: Number of kgsl_command_syncpoints in syncpoint list - * @context_id: Context ID submittin ghte kgsl_gpu_command - * @timestamp: Timestamp for the submitted commands - */ -struct kgsl_gpu_command { - uint64_t flags; - uint64_t __user cmdlist; - unsigned int cmdsize; - unsigned int numcmds; - uint64_t __user objlist; - unsigned int objsize; - unsigned int numobjs; - uint64_t __user synclist; - unsigned int syncsize; - unsigned int numsyncs; - unsigned int context_id; - unsigned int timestamp; -}; - -#define IOCTL_KGSL_GPU_COMMAND \ - _IOWR(KGSL_IOC_TYPE, 0x4A, struct kgsl_gpu_command) - -/** - * struct kgsl_preemption_counters_query - argument to - * IOCTL_KGSL_PREEMPTIONCOUNTER_QUERY - * @counters: Return preemption counters array - * @size_user: Size allocated by userspace - * @size_priority_level: Size of preemption counters for each - * priority level - * @max_priority_level: Return max number of priority levels - * - * Query the available preemption counters. The array counters - * is used to return preemption counters. The size of the array - * is passed in so the kernel will only write at most size_user - * or max available preemption counters. The total number of - * preemption counters is returned in max_priority_level. If the - * array or size passed in are invalid, then an error is - * returned back. - */ -struct kgsl_preemption_counters_query { - uint64_t __user counters; - unsigned int size_user; - unsigned int size_priority_level; - unsigned int max_priority_level; -}; - -#define IOCTL_KGSL_PREEMPTIONCOUNTER_QUERY \ - _IOWR(KGSL_IOC_TYPE, 0x4B, struct kgsl_preemption_counters_query) - -/** - * struct kgsl_gpuobj_set_info - argument for IOCTL_KGSL_GPUOBJ_SET_INFO - * @flags: Flags to indicate which paramaters to change - * @metadata: If KGSL_GPUOBJ_SET_INFO_METADATA is set, a pointer to the new - * metadata - * @id: GPU memory object ID to change - * @metadata_len: If KGSL_GPUOBJ_SET_INFO_METADATA is set, the length of the - * new metadata string - * @type: If KGSL_GPUOBJ_SET_INFO_TYPE is set, the new type of the memory object - */ - -#define KGSL_GPUOBJ_SET_INFO_METADATA (1 << 0) -#define KGSL_GPUOBJ_SET_INFO_TYPE (1 << 1) - -struct kgsl_gpuobj_set_info { - uint64_t flags; - uint64_t metadata; - unsigned int id; - unsigned int metadata_len; - unsigned int type; -}; - -#define IOCTL_KGSL_GPUOBJ_SET_INFO \ - _IOW(KGSL_IOC_TYPE, 0x4C, struct kgsl_gpuobj_set_info) - -#endif /* _UAPI_MSM_KGSL_H */ diff --git a/third_party/linux/include/msm_media_info.h b/third_party/linux/include/msm_media_info.h deleted file mode 100644 index 3fd0c8849a..0000000000 --- a/third_party/linux/include/msm_media_info.h +++ /dev/null @@ -1,1392 +0,0 @@ -#ifndef __MEDIA_INFO_H__ -#define __MEDIA_INFO_H__ - -#ifndef MSM_MEDIA_ALIGN -#define MSM_MEDIA_ALIGN(__sz, __align) (((__align) & ((__align) - 1)) ?\ - ((((__sz) + (__align) - 1) / (__align)) * (__align)) :\ - (((__sz) + (__align) - 1) & (~((__align) - 1)))) -#endif - -#ifndef MSM_MEDIA_ROUNDUP -#define MSM_MEDIA_ROUNDUP(__sz, __r) (((__sz) + ((__r) - 1)) / (__r)) -#endif - -#ifndef MSM_MEDIA_MAX -#define MSM_MEDIA_MAX(__a, __b) ((__a) > (__b)?(__a):(__b)) -#endif - -enum color_fmts { - /* Venus NV12: - * YUV 4:2:0 image with a plane of 8 bit Y samples followed - * by an interleaved U/V plane containing 8 bit 2x2 subsampled - * colour difference samples. - * - * <-------- Y/UV_Stride --------> - * <------- Width -------> - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . ^ ^ - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . Height | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | Y_Scanlines - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . V | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . V - * U V U V U V U V U V U V . . . . ^ - * U V U V U V U V U V U V . . . . | - * U V U V U V U V U V U V . . . . | - * U V U V U V U V U V U V . . . . UV_Scanlines - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . V - * . . . . . . . . . . . . . . . . --> Buffer size alignment - * - * Y_Stride : Width aligned to 128 - * UV_Stride : Width aligned to 128 - * Y_Scanlines: Height aligned to 32 - * UV_Scanlines: Height/2 aligned to 16 - * Extradata: Arbitrary (software-imposed) padding - * Total size = align((Y_Stride * Y_Scanlines - * + UV_Stride * UV_Scanlines - * + max(Extradata, Y_Stride * 8), 4096) - */ - COLOR_FMT_NV12, - - /* Venus NV21: - * YUV 4:2:0 image with a plane of 8 bit Y samples followed - * by an interleaved V/U plane containing 8 bit 2x2 subsampled - * colour difference samples. - * - * <-------- Y/UV_Stride --------> - * <------- Width -------> - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . ^ ^ - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . Height | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | Y_Scanlines - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . V | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . V - * V U V U V U V U V U V U . . . . ^ - * V U V U V U V U V U V U . . . . | - * V U V U V U V U V U V U . . . . | - * V U V U V U V U V U V U . . . . UV_Scanlines - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . V - * . . . . . . . . . . . . . . . . --> Padding & Buffer size alignment - * - * Y_Stride : Width aligned to 128 - * UV_Stride : Width aligned to 128 - * Y_Scanlines: Height aligned to 32 - * UV_Scanlines: Height/2 aligned to 16 - * Extradata: Arbitrary (software-imposed) padding - * Total size = align((Y_Stride * Y_Scanlines - * + UV_Stride * UV_Scanlines - * + max(Extradata, Y_Stride * 8), 4096) - */ - COLOR_FMT_NV21, - /* Venus NV12_MVTB: - * Two YUV 4:2:0 images/views one after the other - * in a top-bottom layout, same as NV12 - * with a plane of 8 bit Y samples followed - * by an interleaved U/V plane containing 8 bit 2x2 subsampled - * colour difference samples. - * - * - * <-------- Y/UV_Stride --------> - * <------- Width -------> - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . ^ ^ ^ - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . Height | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | Y_Scanlines | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . V | | - * . . . . . . . . . . . . . . . . | View_1 - * . . . . . . . . . . . . . . . . | | - * . . . . . . . . . . . . . . . . | | - * . . . . . . . . . . . . . . . . V | - * U V U V U V U V U V U V . . . . ^ | - * U V U V U V U V U V U V . . . . | | - * U V U V U V U V U V U V . . . . | | - * U V U V U V U V U V U V . . . . UV_Scanlines | - * . . . . . . . . . . . . . . . . | | - * . . . . . . . . . . . . . . . . V V - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . ^ ^ ^ - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . Height | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | Y_Scanlines | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . V | | - * . . . . . . . . . . . . . . . . | View_2 - * . . . . . . . . . . . . . . . . | | - * . . . . . . . . . . . . . . . . | | - * . . . . . . . . . . . . . . . . V | - * U V U V U V U V U V U V . . . . ^ | - * U V U V U V U V U V U V . . . . | | - * U V U V U V U V U V U V . . . . | | - * U V U V U V U V U V U V . . . . UV_Scanlines | - * . . . . . . . . . . . . . . . . | | - * . . . . . . . . . . . . . . . . V V - * . . . . . . . . . . . . . . . . --> Buffer size alignment - * - * Y_Stride : Width aligned to 128 - * UV_Stride : Width aligned to 128 - * Y_Scanlines: Height aligned to 32 - * UV_Scanlines: Height/2 aligned to 16 - * View_1 begin at: 0 (zero) - * View_2 begin at: Y_Stride * Y_Scanlines + UV_Stride * UV_Scanlines - * Extradata: Arbitrary (software-imposed) padding - * Total size = align((2*(Y_Stride * Y_Scanlines) - * + 2*(UV_Stride * UV_Scanlines) + Extradata), 4096) - */ - COLOR_FMT_NV12_MVTB, - /* - * The buffer can be of 2 types: - * (1) Venus NV12 UBWC Progressive - * (2) Venus NV12 UBWC Interlaced - * - * (1) Venus NV12 UBWC Progressive Buffer Format: - * Compressed Macro-tile format for NV12. - * Contains 4 planes in the following order - - * (A) Y_Meta_Plane - * (B) Y_UBWC_Plane - * (C) UV_Meta_Plane - * (D) UV_UBWC_Plane - * - * Y_Meta_Plane consists of meta information to decode compressed - * tile data in Y_UBWC_Plane. - * Y_UBWC_Plane consists of Y data in compressed macro-tile format. - * UBWC decoder block will use the Y_Meta_Plane data together with - * Y_UBWC_Plane data to produce loss-less uncompressed 8 bit Y samples. - * - * UV_Meta_Plane consists of meta information to decode compressed - * tile data in UV_UBWC_Plane. - * UV_UBWC_Plane consists of UV data in compressed macro-tile format. - * UBWC decoder block will use UV_Meta_Plane data together with - * UV_UBWC_Plane data to produce loss-less uncompressed 8 bit 2x2 - * subsampled color difference samples. - * - * Each tile in Y_UBWC_Plane/UV_UBWC_Plane is independently decodable - * and randomly accessible. There is no dependency between tiles. - * - * <----- Y_Meta_Stride ----> - * <-------- Width ------> - * M M M M M M M M M M M M . . ^ ^ - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . Height | - * M M M M M M M M M M M M . . | Meta_Y_Scanlines - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . V | - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * . . . . . . . . . . . . . . V - * <--Compressed tile Y Stride---> - * <------- Width -------> - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . ^ ^ - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . Height | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | Macro_tile_Y_Scanlines - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . V | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * . . . . . . . . . . . . . . . . V - * <----- UV_Meta_Stride ----> - * M M M M M M M M M M M M . . ^ - * M M M M M M M M M M M M . . | - * M M M M M M M M M M M M . . | - * M M M M M M M M M M M M . . M_UV_Scanlines - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . V - * . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * <--Compressed tile UV Stride---> - * U* V* U* V* U* V* U* V* . . . . ^ - * U* V* U* V* U* V* U* V* . . . . | - * U* V* U* V* U* V* U* V* . . . . | - * U* V* U* V* U* V* U* V* . . . . UV_Scanlines - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . V - * . . . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * - * Y_Stride = align(Width, 128) - * UV_Stride = align(Width, 128) - * Y_Scanlines = align(Height, 32) - * UV_Scanlines = align(Height/2, 16) - * Y_UBWC_Plane_size = align(Y_Stride * Y_Scanlines, 4096) - * UV_UBWC_Plane_size = align(UV_Stride * UV_Scanlines, 4096) - * Y_Meta_Stride = align(roundup(Width, Y_TileWidth), 64) - * Y_Meta_Scanlines = align(roundup(Height, Y_TileHeight), 16) - * Y_Meta_Plane_size = align(Y_Meta_Stride * Y_Meta_Scanlines, 4096) - * UV_Meta_Stride = align(roundup(Width, UV_TileWidth), 64) - * UV_Meta_Scanlines = align(roundup(Height, UV_TileHeight), 16) - * UV_Meta_Plane_size = align(UV_Meta_Stride * UV_Meta_Scanlines, 4096) - * Extradata = 8k - * - * Total size = align( Y_UBWC_Plane_size + UV_UBWC_Plane_size + - * Y_Meta_Plane_size + UV_Meta_Plane_size - * + max(Extradata, Y_Stride * 48), 4096) - * - * - * (2) Venus NV12 UBWC Interlaced Buffer Format: - * Compressed Macro-tile format for NV12 interlaced. - * Contains 8 planes in the following order - - * (A) Y_Meta_Top_Field_Plane - * (B) Y_UBWC_Top_Field_Plane - * (C) UV_Meta_Top_Field_Plane - * (D) UV_UBWC_Top_Field_Plane - * (E) Y_Meta_Bottom_Field_Plane - * (F) Y_UBWC_Bottom_Field_Plane - * (G) UV_Meta_Bottom_Field_Plane - * (H) UV_UBWC_Bottom_Field_Plane - * Y_Meta_Top_Field_Plane consists of meta information to decode - * compressed tile data for Y_UBWC_Top_Field_Plane. - * Y_UBWC_Top_Field_Plane consists of Y data in compressed macro-tile - * format for top field of an interlaced frame. - * UBWC decoder block will use the Y_Meta_Top_Field_Plane data together - * with Y_UBWC_Top_Field_Plane data to produce loss-less uncompressed - * 8 bit Y samples for top field of an interlaced frame. - * - * UV_Meta_Top_Field_Plane consists of meta information to decode - * compressed tile data in UV_UBWC_Top_Field_Plane. - * UV_UBWC_Top_Field_Plane consists of UV data in compressed macro-tile - * format for top field of an interlaced frame. - * UBWC decoder block will use UV_Meta_Top_Field_Plane data together - * with UV_UBWC_Top_Field_Plane data to produce loss-less uncompressed - * 8 bit subsampled color difference samples for top field of an - * interlaced frame. - * - * Each tile in Y_UBWC_Top_Field_Plane/UV_UBWC_Top_Field_Plane is - * independently decodable and randomly accessible. There is no - * dependency between tiles. - * - * Y_Meta_Bottom_Field_Plane consists of meta information to decode - * compressed tile data for Y_UBWC_Bottom_Field_Plane. - * Y_UBWC_Bottom_Field_Plane consists of Y data in compressed macro-tile - * format for bottom field of an interlaced frame. - * UBWC decoder block will use the Y_Meta_Bottom_Field_Plane data - * together with Y_UBWC_Bottom_Field_Plane data to produce loss-less - * uncompressed 8 bit Y samples for bottom field of an interlaced frame. - * - * UV_Meta_Bottom_Field_Plane consists of meta information to decode - * compressed tile data in UV_UBWC_Bottom_Field_Plane. - * UV_UBWC_Bottom_Field_Plane consists of UV data in compressed - * macro-tile format for bottom field of an interlaced frame. - * UBWC decoder block will use UV_Meta_Bottom_Field_Plane data together - * with UV_UBWC_Bottom_Field_Plane data to produce loss-less - * uncompressed 8 bit subsampled color difference samples for bottom - * field of an interlaced frame. - * - * Each tile in Y_UBWC_Bottom_Field_Plane/UV_UBWC_Bottom_Field_Plane is - * independently decodable and randomly accessible. There is no - * dependency between tiles. - * - * <-----Y_TF_Meta_Stride----> - * <-------- Width ------> - * M M M M M M M M M M M M . . ^ ^ - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . Half_height | - * M M M M M M M M M M M M . . | Meta_Y_TF_Scanlines - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . V | - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * . . . . . . . . . . . . . . V - * <-Compressed tile Y_TF Stride-> - * <------- Width -------> - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . ^ ^ - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . Half_height | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | Macro_tile_Y_TF_Scanlines - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . V | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * . . . . . . . . . . . . . . . . V - * <----UV_TF_Meta_Stride----> - * M M M M M M M M M M M M . . ^ - * M M M M M M M M M M M M . . | - * M M M M M M M M M M M M . . | - * M M M M M M M M M M M M . . M_UV_TF_Scanlines - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . V - * . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * <-Compressed tile UV_TF Stride-> - * U* V* U* V* U* V* U* V* . . . . ^ - * U* V* U* V* U* V* U* V* . . . . | - * U* V* U* V* U* V* U* V* . . . . | - * U* V* U* V* U* V* U* V* . . . . UV_TF_Scanlines - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . V - * . . . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * <-----Y_BF_Meta_Stride----> - * <-------- Width ------> - * M M M M M M M M M M M M . . ^ ^ - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . Half_height | - * M M M M M M M M M M M M . . | Meta_Y_BF_Scanlines - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . V | - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * . . . . . . . . . . . . . . V - * <-Compressed tile Y_BF Stride-> - * <------- Width -------> - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . ^ ^ - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . Half_height | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | Macro_tile_Y_BF_Scanlines - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . V | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * . . . . . . . . . . . . . . . . V - * <----UV_BF_Meta_Stride----> - * M M M M M M M M M M M M . . ^ - * M M M M M M M M M M M M . . | - * M M M M M M M M M M M M . . | - * M M M M M M M M M M M M . . M_UV_BF_Scanlines - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . V - * . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * <-Compressed tile UV_BF Stride-> - * U* V* U* V* U* V* U* V* . . . . ^ - * U* V* U* V* U* V* U* V* . . . . | - * U* V* U* V* U* V* U* V* . . . . | - * U* V* U* V* U* V* U* V* . . . . UV_BF_Scanlines - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . V - * . . . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * - * Half_height = (Height+1)>>1 - * Y_TF_Stride = align(Width, 128) - * UV_TF_Stride = align(Width, 128) - * Y_TF_Scanlines = align(Half_height, 32) - * UV_TF_Scanlines = align((Half_height+1)/2, 32) - * Y_UBWC_TF_Plane_size = align(Y_TF_Stride * Y_TF_Scanlines, 4096) - * UV_UBWC_TF_Plane_size = align(UV_TF_Stride * UV_TF_Scanlines, 4096) - * Y_TF_Meta_Stride = align(roundup(Width, Y_TileWidth), 64) - * Y_TF_Meta_Scanlines = align(roundup(Half_height, Y_TileHeight), 16) - * Y_TF_Meta_Plane_size = - * align(Y_TF_Meta_Stride * Y_TF_Meta_Scanlines, 4096) - * UV_TF_Meta_Stride = align(roundup(Width, UV_TileWidth), 64) - * UV_TF_Meta_Scanlines = align(roundup(Half_height, UV_TileHeight), 16) - * UV_TF_Meta_Plane_size = - * align(UV_TF_Meta_Stride * UV_TF_Meta_Scanlines, 4096) - * Y_BF_Stride = align(Width, 128) - * UV_BF_Stride = align(Width, 128) - * Y_BF_Scanlines = align(Half_height, 32) - * UV_BF_Scanlines = align((Half_height+1)/2, 32) - * Y_UBWC_BF_Plane_size = align(Y_BF_Stride * Y_BF_Scanlines, 4096) - * UV_UBWC_BF_Plane_size = align(UV_BF_Stride * UV_BF_Scanlines, 4096) - * Y_BF_Meta_Stride = align(roundup(Width, Y_TileWidth), 64) - * Y_BF_Meta_Scanlines = align(roundup(Half_height, Y_TileHeight), 16) - * Y_BF_Meta_Plane_size = - * align(Y_BF_Meta_Stride * Y_BF_Meta_Scanlines, 4096) - * UV_BF_Meta_Stride = align(roundup(Width, UV_TileWidth), 64) - * UV_BF_Meta_Scanlines = align(roundup(Half_height, UV_TileHeight), 16) - * UV_BF_Meta_Plane_size = - * align(UV_BF_Meta_Stride * UV_BF_Meta_Scanlines, 4096) - * Extradata = 8k - * - * Total size = align( Y_UBWC_TF_Plane_size + UV_UBWC_TF_Plane_size + - * Y_TF_Meta_Plane_size + UV_TF_Meta_Plane_size + - * Y_UBWC_BF_Plane_size + UV_UBWC_BF_Plane_size + - * Y_BF_Meta_Plane_size + UV_BF_Meta_Plane_size + - * + max(Extradata, Y_TF_Stride * 48), 4096) - */ - COLOR_FMT_NV12_UBWC, - /* Venus NV12 10-bit UBWC: - * Compressed Macro-tile format for NV12. - * Contains 4 planes in the following order - - * (A) Y_Meta_Plane - * (B) Y_UBWC_Plane - * (C) UV_Meta_Plane - * (D) UV_UBWC_Plane - * - * Y_Meta_Plane consists of meta information to decode compressed - * tile data in Y_UBWC_Plane. - * Y_UBWC_Plane consists of Y data in compressed macro-tile format. - * UBWC decoder block will use the Y_Meta_Plane data together with - * Y_UBWC_Plane data to produce loss-less uncompressed 10 bit Y samples. - * - * UV_Meta_Plane consists of meta information to decode compressed - * tile data in UV_UBWC_Plane. - * UV_UBWC_Plane consists of UV data in compressed macro-tile format. - * UBWC decoder block will use UV_Meta_Plane data together with - * UV_UBWC_Plane data to produce loss-less uncompressed 10 bit 2x2 - * subsampled color difference samples. - * - * Each tile in Y_UBWC_Plane/UV_UBWC_Plane is independently decodable - * and randomly accessible. There is no dependency between tiles. - * - * <----- Y_Meta_Stride -----> - * <-------- Width ------> - * M M M M M M M M M M M M . . ^ ^ - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . Height | - * M M M M M M M M M M M M . . | Meta_Y_Scanlines - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . V | - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * . . . . . . . . . . . . . . V - * <--Compressed tile Y Stride---> - * <------- Width -------> - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . ^ ^ - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . Height | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | Macro_tile_Y_Scanlines - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . V | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * . . . . . . . . . . . . . . . . V - * <----- UV_Meta_Stride ----> - * M M M M M M M M M M M M . . ^ - * M M M M M M M M M M M M . . | - * M M M M M M M M M M M M . . | - * M M M M M M M M M M M M . . M_UV_Scanlines - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . V - * . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * <--Compressed tile UV Stride---> - * U* V* U* V* U* V* U* V* . . . . ^ - * U* V* U* V* U* V* U* V* . . . . | - * U* V* U* V* U* V* U* V* . . . . | - * U* V* U* V* U* V* U* V* . . . . UV_Scanlines - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . V - * . . . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * - * - * Y_Stride = align(Width * 4/3, 128) - * UV_Stride = align(Width * 4/3, 128) - * Y_Scanlines = align(Height, 32) - * UV_Scanlines = align(Height/2, 16) - * Y_UBWC_Plane_Size = align(Y_Stride * Y_Scanlines, 4096) - * UV_UBWC_Plane_Size = align(UV_Stride * UV_Scanlines, 4096) - * Y_Meta_Stride = align(roundup(Width, Y_TileWidth), 64) - * Y_Meta_Scanlines = align(roundup(Height, Y_TileHeight), 16) - * Y_Meta_Plane_size = align(Y_Meta_Stride * Y_Meta_Scanlines, 4096) - * UV_Meta_Stride = align(roundup(Width, UV_TileWidth), 64) - * UV_Meta_Scanlines = align(roundup(Height, UV_TileHeight), 16) - * UV_Meta_Plane_size = align(UV_Meta_Stride * UV_Meta_Scanlines, 4096) - * Extradata = 8k - * - * Total size = align(Y_UBWC_Plane_size + UV_UBWC_Plane_size + - * Y_Meta_Plane_size + UV_Meta_Plane_size - * + max(Extradata, Y_Stride * 48), 4096) - */ - COLOR_FMT_NV12_BPP10_UBWC, - /* Venus RGBA8888 format: - * Contains 1 plane in the following order - - * (A) RGBA plane - * - * <-------- RGB_Stride --------> - * <------- Width -------> - * R R R R R R R R R R R R . . . . ^ ^ - * R R R R R R R R R R R R . . . . | | - * R R R R R R R R R R R R . . . . Height | - * R R R R R R R R R R R R . . . . | RGB_Scanlines - * R R R R R R R R R R R R . . . . | | - * R R R R R R R R R R R R . . . . | | - * R R R R R R R R R R R R . . . . | | - * R R R R R R R R R R R R . . . . V | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . V - * - * RGB_Stride = align(Width * 4, 128) - * RGB_Scanlines = align(Height, 32) - * RGB_Plane_size = align(RGB_Stride * RGB_Scanlines, 4096) - * Extradata = 8k - * - * Total size = align(RGB_Plane_size + Extradata, 4096) - */ - COLOR_FMT_RGBA8888, - /* Venus RGBA8888 UBWC format: - * Contains 2 planes in the following order - - * (A) Meta plane - * (B) RGBA plane - * - * <--- RGB_Meta_Stride ----> - * <-------- Width ------> - * M M M M M M M M M M M M . . ^ ^ - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . Height | - * M M M M M M M M M M M M . . | Meta_RGB_Scanlines - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . V | - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * . . . . . . . . . . . . . . V - * <-------- RGB_Stride --------> - * <------- Width -------> - * R R R R R R R R R R R R . . . . ^ ^ - * R R R R R R R R R R R R . . . . | | - * R R R R R R R R R R R R . . . . Height | - * R R R R R R R R R R R R . . . . | RGB_Scanlines - * R R R R R R R R R R R R . . . . | | - * R R R R R R R R R R R R . . . . | | - * R R R R R R R R R R R R . . . . | | - * R R R R R R R R R R R R . . . . V | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * . . . . . . . . . . . . . . . . V - * - * RGB_Stride = align(Width * 4, 128) - * RGB_Scanlines = align(Height, 32) - * RGB_Plane_size = align(RGB_Stride * RGB_Scanlines, 4096) - * RGB_Meta_Stride = align(roundup(Width, RGB_TileWidth), 64) - * RGB_Meta_Scanline = align(roundup(Height, RGB_TileHeight), 16) - * RGB_Meta_Plane_size = align(RGB_Meta_Stride * - * RGB_Meta_Scanlines, 4096) - * Extradata = 8k - * - * Total size = align(RGB_Meta_Plane_size + RGB_Plane_size + - * Extradata, 4096) - */ - COLOR_FMT_RGBA8888_UBWC, - /* Venus RGBA1010102 UBWC format: - * Contains 2 planes in the following order - - * (A) Meta plane - * (B) RGBA plane - * - * <--- RGB_Meta_Stride ----> - * <-------- Width ------> - * M M M M M M M M M M M M . . ^ ^ - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . Height | - * M M M M M M M M M M M M . . | Meta_RGB_Scanlines - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . V | - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * . . . . . . . . . . . . . . V - * <-------- RGB_Stride --------> - * <------- Width -------> - * R R R R R R R R R R R R . . . . ^ ^ - * R R R R R R R R R R R R . . . . | | - * R R R R R R R R R R R R . . . . Height | - * R R R R R R R R R R R R . . . . | RGB_Scanlines - * R R R R R R R R R R R R . . . . | | - * R R R R R R R R R R R R . . . . | | - * R R R R R R R R R R R R . . . . | | - * R R R R R R R R R R R R . . . . V | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * . . . . . . . . . . . . . . . . V - * - * RGB_Stride = align(Width * 4, 256) - * RGB_Scanlines = align(Height, 16) - * RGB_Plane_size = align(RGB_Stride * RGB_Scanlines, 4096) - * RGB_Meta_Stride = align(roundup(Width, RGB_TileWidth), 64) - * RGB_Meta_Scanline = align(roundup(Height, RGB_TileHeight), 16) - * RGB_Meta_Plane_size = align(RGB_Meta_Stride * - * RGB_Meta_Scanlines, 4096) - * Extradata = 8k - * - * Total size = align(RGB_Meta_Plane_size + RGB_Plane_size + - * Extradata, 4096) - */ - COLOR_FMT_RGBA1010102_UBWC, - /* Venus RGB565 UBWC format: - * Contains 2 planes in the following order - - * (A) Meta plane - * (B) RGB plane - * - * <--- RGB_Meta_Stride ----> - * <-------- Width ------> - * M M M M M M M M M M M M . . ^ ^ - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . Height | - * M M M M M M M M M M M M . . | Meta_RGB_Scanlines - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . V | - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * . . . . . . . . . . . . . . V - * <-------- RGB_Stride --------> - * <------- Width -------> - * R R R R R R R R R R R R . . . . ^ ^ - * R R R R R R R R R R R R . . . . | | - * R R R R R R R R R R R R . . . . Height | - * R R R R R R R R R R R R . . . . | RGB_Scanlines - * R R R R R R R R R R R R . . . . | | - * R R R R R R R R R R R R . . . . | | - * R R R R R R R R R R R R . . . . | | - * R R R R R R R R R R R R . . . . V | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * . . . . . . . . . . . . . . . . V - * - * RGB_Stride = align(Width * 2, 128) - * RGB_Scanlines = align(Height, 16) - * RGB_Plane_size = align(RGB_Stride * RGB_Scanlines, 4096) - * RGB_Meta_Stride = align(roundup(Width, RGB_TileWidth), 64) - * RGB_Meta_Scanline = align(roundup(Height, RGB_TileHeight), 16) - * RGB_Meta_Plane_size = align(RGB_Meta_Stride * - * RGB_Meta_Scanlines, 4096) - * Extradata = 8k - * - * Total size = align(RGB_Meta_Plane_size + RGB_Plane_size + - * Extradata, 4096) - */ - COLOR_FMT_RGB565_UBWC, - /* P010 UBWC: - * Compressed Macro-tile format for NV12. - * Contains 4 planes in the following order - - * (A) Y_Meta_Plane - * (B) Y_UBWC_Plane - * (C) UV_Meta_Plane - * (D) UV_UBWC_Plane - * - * Y_Meta_Plane consists of meta information to decode compressed - * tile data in Y_UBWC_Plane. - * Y_UBWC_Plane consists of Y data in compressed macro-tile format. - * UBWC decoder block will use the Y_Meta_Plane data together with - * Y_UBWC_Plane data to produce loss-less uncompressed 10 bit Y samples. - * - * UV_Meta_Plane consists of meta information to decode compressed - * tile data in UV_UBWC_Plane. - * UV_UBWC_Plane consists of UV data in compressed macro-tile format. - * UBWC decoder block will use UV_Meta_Plane data together with - * UV_UBWC_Plane data to produce loss-less uncompressed 10 bit 2x2 - * subsampled color difference samples. - * - * Each tile in Y_UBWC_Plane/UV_UBWC_Plane is independently decodable - * and randomly accessible. There is no dependency between tiles. - * - * <----- Y_Meta_Stride -----> - * <-------- Width ------> - * M M M M M M M M M M M M . . ^ ^ - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . Height | - * M M M M M M M M M M M M . . | Meta_Y_Scanlines - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . V | - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * . . . . . . . . . . . . . . V - * <--Compressed tile Y Stride---> - * <------- Width -------> - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . ^ ^ - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . Height | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | Macro_tile_Y_Scanlines - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . V | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * . . . . . . . . . . . . . . . . V - * <----- UV_Meta_Stride ----> - * M M M M M M M M M M M M . . ^ - * M M M M M M M M M M M M . . | - * M M M M M M M M M M M M . . | - * M M M M M M M M M M M M . . M_UV_Scanlines - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . V - * . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * <--Compressed tile UV Stride---> - * U* V* U* V* U* V* U* V* . . . . ^ - * U* V* U* V* U* V* U* V* . . . . | - * U* V* U* V* U* V* U* V* . . . . | - * U* V* U* V* U* V* U* V* . . . . UV_Scanlines - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . V - * . . . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * - * - * Y_Stride = align(Width * 2, 256) - * UV_Stride = align(Width * 2, 256) - * Y_Scanlines = align(Height, 16) - * UV_Scanlines = align(Height/2, 16) - * Y_UBWC_Plane_Size = align(Y_Stride * Y_Scanlines, 4096) - * UV_UBWC_Plane_Size = align(UV_Stride * UV_Scanlines, 4096) - * Y_Meta_Stride = align(roundup(Width, Y_TileWidth), 64) - * Y_Meta_Scanlines = align(roundup(Height, Y_TileHeight), 16) - * Y_Meta_Plane_size = align(Y_Meta_Stride * Y_Meta_Scanlines, 4096) - * UV_Meta_Stride = align(roundup(Width, UV_TileWidth), 64) - * UV_Meta_Scanlines = align(roundup(Height, UV_TileHeight), 16) - * UV_Meta_Plane_size = align(UV_Meta_Stride * UV_Meta_Scanlines, 4096) - * Extradata = 8k - * - * Total size = align(Y_UBWC_Plane_size + UV_UBWC_Plane_size + - * Y_Meta_Plane_size + UV_Meta_Plane_size - * + max(Extradata, Y_Stride * 48), 4096) - */ - COLOR_FMT_P010_UBWC, - /* Venus P010: - * YUV 4:2:0 image with a plane of 10 bit Y samples followed - * by an interleaved U/V plane containing 10 bit 2x2 subsampled - * colour difference samples. - * - * <-------- Y/UV_Stride --------> - * <------- Width -------> - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . ^ ^ - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . Height | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | Y_Scanlines - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . V | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . V - * U V U V U V U V U V U V . . . . ^ - * U V U V U V U V U V U V . . . . | - * U V U V U V U V U V U V . . . . | - * U V U V U V U V U V U V . . . . UV_Scanlines - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . V - * . . . . . . . . . . . . . . . . --> Buffer size alignment - * - * Y_Stride : Width * 2 aligned to 128 - * UV_Stride : Width * 2 aligned to 128 - * Y_Scanlines: Height aligned to 32 - * UV_Scanlines: Height/2 aligned to 16 - * Extradata: Arbitrary (software-imposed) padding - * Total size = align((Y_Stride * Y_Scanlines - * + UV_Stride * UV_Scanlines - * + max(Extradata, Y_Stride * 8), 4096) - */ - COLOR_FMT_P010, -}; - -#define COLOR_FMT_RGBA1010102_UBWC COLOR_FMT_RGBA1010102_UBWC -#define COLOR_FMT_RGB565_UBWC COLOR_FMT_RGB565_UBWC -#define COLOR_FMT_P010_UBWC COLOR_FMT_P010_UBWC -#define COLOR_FMT_P010 COLOR_FMT_P010 - -static inline unsigned int VENUS_EXTRADATA_SIZE(int width, int height) -{ - (void)height; - (void)width; - - /* - * In the future, calculate the size based on the w/h but just - * hardcode it for now since 16K satisfies all current usecases. - */ - return 16 * 1024; -} - -/* - * Function arguments: - * @color_fmt - * @width - * Progressive: width - * Interlaced: width - */ -static inline unsigned int VENUS_Y_STRIDE(int color_fmt, int width) -{ - unsigned int alignment, stride = 0; - - if (!width) - goto invalid_input; - - switch (color_fmt) { - case COLOR_FMT_NV21: - case COLOR_FMT_NV12: - case COLOR_FMT_NV12_MVTB: - case COLOR_FMT_NV12_UBWC: - alignment = 128; - stride = MSM_MEDIA_ALIGN(width, alignment); - break; - case COLOR_FMT_NV12_BPP10_UBWC: - alignment = 256; - stride = MSM_MEDIA_ALIGN(width, 192); - stride = MSM_MEDIA_ALIGN(stride * 4/3, alignment); - break; - case COLOR_FMT_P010_UBWC: - alignment = 256; - stride = MSM_MEDIA_ALIGN(width * 2, alignment); - break; - case COLOR_FMT_P010: - alignment = 128; - stride = MSM_MEDIA_ALIGN(width*2, alignment); - break; - default: - break; - } -invalid_input: - return stride; -} - -/* - * Function arguments: - * @color_fmt - * @width - * Progressive: width - * Interlaced: width - */ -static inline unsigned int VENUS_UV_STRIDE(int color_fmt, int width) -{ - unsigned int alignment, stride = 0; - - if (!width) - goto invalid_input; - - switch (color_fmt) { - case COLOR_FMT_NV21: - case COLOR_FMT_NV12: - case COLOR_FMT_NV12_MVTB: - case COLOR_FMT_NV12_UBWC: - alignment = 128; - stride = MSM_MEDIA_ALIGN(width, alignment); - break; - case COLOR_FMT_NV12_BPP10_UBWC: - alignment = 256; - stride = MSM_MEDIA_ALIGN(width, 192); - stride = MSM_MEDIA_ALIGN(stride * 4/3, alignment); - break; - case COLOR_FMT_P010_UBWC: - alignment = 256; - stride = MSM_MEDIA_ALIGN(width * 2, alignment); - break; - case COLOR_FMT_P010: - alignment = 128; - stride = MSM_MEDIA_ALIGN(width*2, alignment); - break; - default: - break; - } -invalid_input: - return stride; -} - -/* - * Function arguments: - * @color_fmt - * @height - * Progressive: height - * Interlaced: (height+1)>>1 - */ -static inline unsigned int VENUS_Y_SCANLINES(int color_fmt, int height) -{ - unsigned int alignment, sclines = 0; - - if (!height) - goto invalid_input; - - switch (color_fmt) { - case COLOR_FMT_NV21: - case COLOR_FMT_NV12: - case COLOR_FMT_NV12_MVTB: - case COLOR_FMT_NV12_UBWC: - case COLOR_FMT_P010: - alignment = 32; - break; - case COLOR_FMT_NV12_BPP10_UBWC: - case COLOR_FMT_P010_UBWC: - alignment = 16; - break; - default: - return 0; - } - sclines = MSM_MEDIA_ALIGN(height, alignment); -invalid_input: - return sclines; -} - -/* - * Function arguments: - * @color_fmt - * @height - * Progressive: height - * Interlaced: (height+1)>>1 - */ -static inline unsigned int VENUS_UV_SCANLINES(int color_fmt, int height) -{ - unsigned int alignment, sclines = 0; - - if (!height) - goto invalid_input; - - switch (color_fmt) { - case COLOR_FMT_NV21: - case COLOR_FMT_NV12: - case COLOR_FMT_NV12_MVTB: - case COLOR_FMT_NV12_BPP10_UBWC: - case COLOR_FMT_P010_UBWC: - case COLOR_FMT_P010: - alignment = 16; - break; - case COLOR_FMT_NV12_UBWC: - alignment = 32; - break; - default: - goto invalid_input; - } - - sclines = MSM_MEDIA_ALIGN((height+1)>>1, alignment); - -invalid_input: - return sclines; -} - -/* - * Function arguments: - * @color_fmt - * @width - * Progressive: width - * Interlaced: width - */ -static inline unsigned int VENUS_Y_META_STRIDE(int color_fmt, int width) -{ - int y_tile_width = 0, y_meta_stride = 0; - - if (!width) - goto invalid_input; - - switch (color_fmt) { - case COLOR_FMT_NV12_UBWC: - case COLOR_FMT_P010_UBWC: - y_tile_width = 32; - break; - case COLOR_FMT_NV12_BPP10_UBWC: - y_tile_width = 48; - break; - default: - goto invalid_input; - } - - y_meta_stride = MSM_MEDIA_ROUNDUP(width, y_tile_width); - y_meta_stride = MSM_MEDIA_ALIGN(y_meta_stride, 64); - -invalid_input: - return y_meta_stride; -} - -/* - * Function arguments: - * @color_fmt - * @height - * Progressive: height - * Interlaced: (height+1)>>1 - */ -static inline unsigned int VENUS_Y_META_SCANLINES(int color_fmt, int height) -{ - int y_tile_height = 0, y_meta_scanlines = 0; - - if (!height) - goto invalid_input; - - switch (color_fmt) { - case COLOR_FMT_NV12_UBWC: - y_tile_height = 8; - break; - case COLOR_FMT_NV12_BPP10_UBWC: - case COLOR_FMT_P010_UBWC: - y_tile_height = 4; - break; - default: - goto invalid_input; - } - - y_meta_scanlines = MSM_MEDIA_ROUNDUP(height, y_tile_height); - y_meta_scanlines = MSM_MEDIA_ALIGN(y_meta_scanlines, 16); - -invalid_input: - return y_meta_scanlines; -} - -/* - * Function arguments: - * @color_fmt - * @width - * Progressive: width - * Interlaced: width - */ -static inline unsigned int VENUS_UV_META_STRIDE(int color_fmt, int width) -{ - int uv_tile_width = 0, uv_meta_stride = 0; - - if (!width) - goto invalid_input; - - switch (color_fmt) { - case COLOR_FMT_NV12_UBWC: - case COLOR_FMT_P010_UBWC: - uv_tile_width = 16; - break; - case COLOR_FMT_NV12_BPP10_UBWC: - uv_tile_width = 24; - break; - default: - goto invalid_input; - } - - uv_meta_stride = MSM_MEDIA_ROUNDUP((width+1)>>1, uv_tile_width); - uv_meta_stride = MSM_MEDIA_ALIGN(uv_meta_stride, 64); - -invalid_input: - return uv_meta_stride; -} - -/* - * Function arguments: - * @color_fmt - * @height - * Progressive: height - * Interlaced: (height+1)>>1 - */ -static inline unsigned int VENUS_UV_META_SCANLINES(int color_fmt, int height) -{ - int uv_tile_height = 0, uv_meta_scanlines = 0; - - if (!height) - goto invalid_input; - - switch (color_fmt) { - case COLOR_FMT_NV12_UBWC: - uv_tile_height = 8; - break; - case COLOR_FMT_NV12_BPP10_UBWC: - case COLOR_FMT_P010_UBWC: - uv_tile_height = 4; - break; - default: - goto invalid_input; - } - - uv_meta_scanlines = MSM_MEDIA_ROUNDUP((height+1)>>1, uv_tile_height); - uv_meta_scanlines = MSM_MEDIA_ALIGN(uv_meta_scanlines, 16); - -invalid_input: - return uv_meta_scanlines; -} - -static inline unsigned int VENUS_RGB_STRIDE(int color_fmt, int width) -{ - unsigned int alignment = 0, stride = 0, bpp = 4; - - if (!width) - goto invalid_input; - - switch (color_fmt) { - case COLOR_FMT_RGBA8888: - alignment = 128; - break; - case COLOR_FMT_RGB565_UBWC: - alignment = 256; - bpp = 2; - break; - case COLOR_FMT_RGBA8888_UBWC: - case COLOR_FMT_RGBA1010102_UBWC: - alignment = 256; - break; - default: - goto invalid_input; - } - - stride = MSM_MEDIA_ALIGN(width * bpp, alignment); - -invalid_input: - return stride; -} - -static inline unsigned int VENUS_RGB_SCANLINES(int color_fmt, int height) -{ - unsigned int alignment = 0, scanlines = 0; - - if (!height) - goto invalid_input; - - switch (color_fmt) { - case COLOR_FMT_RGBA8888: - alignment = 32; - break; - case COLOR_FMT_RGBA8888_UBWC: - case COLOR_FMT_RGBA1010102_UBWC: - case COLOR_FMT_RGB565_UBWC: - alignment = 16; - break; - default: - goto invalid_input; - } - - scanlines = MSM_MEDIA_ALIGN(height, alignment); - -invalid_input: - return scanlines; -} - -static inline unsigned int VENUS_RGB_META_STRIDE(int color_fmt, int width) -{ - int rgb_tile_width = 0, rgb_meta_stride = 0; - - if (!width) - goto invalid_input; - - switch (color_fmt) { - case COLOR_FMT_RGBA8888_UBWC: - case COLOR_FMT_RGBA1010102_UBWC: - case COLOR_FMT_RGB565_UBWC: - rgb_tile_width = 16; - break; - default: - goto invalid_input; - } - - rgb_meta_stride = MSM_MEDIA_ROUNDUP(width, rgb_tile_width); - rgb_meta_stride = MSM_MEDIA_ALIGN(rgb_meta_stride, 64); - -invalid_input: - return rgb_meta_stride; -} - -static inline unsigned int VENUS_RGB_META_SCANLINES(int color_fmt, int height) -{ - int rgb_tile_height = 0, rgb_meta_scanlines = 0; - - if (!height) - goto invalid_input; - - switch (color_fmt) { - case COLOR_FMT_RGBA8888_UBWC: - case COLOR_FMT_RGBA1010102_UBWC: - case COLOR_FMT_RGB565_UBWC: - rgb_tile_height = 4; - break; - default: - goto invalid_input; - } - - rgb_meta_scanlines = MSM_MEDIA_ROUNDUP(height, rgb_tile_height); - rgb_meta_scanlines = MSM_MEDIA_ALIGN(rgb_meta_scanlines, 16); - -invalid_input: - return rgb_meta_scanlines; -} - -/* - * Function arguments: - * @color_fmt - * @width - * Progressive: width - * Interlaced: width - * @height - * Progressive: height - * Interlaced: height - */ -static inline unsigned int VENUS_BUFFER_SIZE( - int color_fmt, int width, int height) -{ - const unsigned int extra_size = VENUS_EXTRADATA_SIZE(width, height); - unsigned int uv_alignment = 0, size = 0; - unsigned int w_alignment = 512; - unsigned int y_plane, uv_plane, y_stride, - uv_stride, y_sclines, uv_sclines; - unsigned int y_ubwc_plane = 0, uv_ubwc_plane = 0; - unsigned int y_meta_stride = 0, y_meta_scanlines = 0; - unsigned int uv_meta_stride = 0, uv_meta_scanlines = 0; - unsigned int y_meta_plane = 0, uv_meta_plane = 0; - unsigned int rgb_stride = 0, rgb_scanlines = 0; - unsigned int rgb_plane = 0, rgb_ubwc_plane = 0, rgb_meta_plane = 0; - unsigned int rgb_meta_stride = 0, rgb_meta_scanlines = 0; - - if (!width || !height) - goto invalid_input; - - y_stride = VENUS_Y_STRIDE(color_fmt, width); - uv_stride = VENUS_UV_STRIDE(color_fmt, width); - y_sclines = VENUS_Y_SCANLINES(color_fmt, height); - uv_sclines = VENUS_UV_SCANLINES(color_fmt, height); - rgb_stride = VENUS_RGB_STRIDE(color_fmt, width); - rgb_scanlines = VENUS_RGB_SCANLINES(color_fmt, height); - - switch (color_fmt) { - case COLOR_FMT_NV21: - case COLOR_FMT_NV12: - uv_alignment = 4096; - y_plane = y_stride * y_sclines; - uv_plane = uv_stride * uv_sclines + uv_alignment; - size = y_plane + uv_plane + - MSM_MEDIA_MAX(extra_size, 8 * y_stride); - size = MSM_MEDIA_ALIGN(size, 4096); - - /* Additional size to cover last row of non-aligned frame */ - size += MSM_MEDIA_ALIGN(width, w_alignment) * w_alignment; - size = MSM_MEDIA_ALIGN(size, 4096); - break; - case COLOR_FMT_P010: - uv_alignment = 4096; - y_plane = y_stride * y_sclines; - uv_plane = uv_stride * uv_sclines + uv_alignment; - size = y_plane + uv_plane + - MSM_MEDIA_MAX(extra_size, 8 * y_stride); - size = MSM_MEDIA_ALIGN(size, 4096); - break; - case COLOR_FMT_NV12_MVTB: - uv_alignment = 4096; - y_plane = y_stride * y_sclines; - uv_plane = uv_stride * uv_sclines + uv_alignment; - size = y_plane + uv_plane; - size = 2 * size + extra_size; - size = MSM_MEDIA_ALIGN(size, 4096); - break; - case COLOR_FMT_NV12_UBWC: - y_sclines = VENUS_Y_SCANLINES(color_fmt, (height+1)>>1); - y_ubwc_plane = MSM_MEDIA_ALIGN(y_stride * y_sclines, 4096); - uv_sclines = VENUS_UV_SCANLINES(color_fmt, (height+1)>>1); - uv_ubwc_plane = MSM_MEDIA_ALIGN(uv_stride * uv_sclines, 4096); - y_meta_stride = VENUS_Y_META_STRIDE(color_fmt, width); - y_meta_scanlines = - VENUS_Y_META_SCANLINES(color_fmt, (height+1)>>1); - y_meta_plane = MSM_MEDIA_ALIGN( - y_meta_stride * y_meta_scanlines, 4096); - uv_meta_stride = VENUS_UV_META_STRIDE(color_fmt, width); - uv_meta_scanlines = - VENUS_UV_META_SCANLINES(color_fmt, (height+1)>>1); - uv_meta_plane = MSM_MEDIA_ALIGN(uv_meta_stride * - uv_meta_scanlines, 4096); - - size = (y_ubwc_plane + uv_ubwc_plane + y_meta_plane + - uv_meta_plane)*2 + - MSM_MEDIA_MAX(extra_size + 8192, 48 * y_stride); - size = MSM_MEDIA_ALIGN(size, 4096); - - /* Additional size to cover last row of non-aligned frame */ - size += MSM_MEDIA_ALIGN(width, w_alignment) * w_alignment; - size = MSM_MEDIA_ALIGN(size, 4096); - break; - case COLOR_FMT_NV12_BPP10_UBWC: - y_ubwc_plane = MSM_MEDIA_ALIGN(y_stride * y_sclines, 4096); - uv_ubwc_plane = MSM_MEDIA_ALIGN(uv_stride * uv_sclines, 4096); - y_meta_stride = VENUS_Y_META_STRIDE(color_fmt, width); - y_meta_scanlines = VENUS_Y_META_SCANLINES(color_fmt, height); - y_meta_plane = MSM_MEDIA_ALIGN( - y_meta_stride * y_meta_scanlines, 4096); - uv_meta_stride = VENUS_UV_META_STRIDE(color_fmt, width); - uv_meta_scanlines = VENUS_UV_META_SCANLINES(color_fmt, height); - uv_meta_plane = MSM_MEDIA_ALIGN(uv_meta_stride * - uv_meta_scanlines, 4096); - - size = y_ubwc_plane + uv_ubwc_plane + y_meta_plane + - uv_meta_plane + - MSM_MEDIA_MAX(extra_size + 8192, 48 * y_stride); - size = MSM_MEDIA_ALIGN(size, 4096); - break; - case COLOR_FMT_P010_UBWC: - y_ubwc_plane = MSM_MEDIA_ALIGN(y_stride * y_sclines, 4096); - uv_ubwc_plane = MSM_MEDIA_ALIGN(uv_stride * uv_sclines, 4096); - y_meta_stride = VENUS_Y_META_STRIDE(color_fmt, width); - y_meta_scanlines = VENUS_Y_META_SCANLINES(color_fmt, height); - y_meta_plane = MSM_MEDIA_ALIGN( - y_meta_stride * y_meta_scanlines, 4096); - uv_meta_stride = VENUS_UV_META_STRIDE(color_fmt, width); - uv_meta_scanlines = VENUS_UV_META_SCANLINES(color_fmt, height); - uv_meta_plane = MSM_MEDIA_ALIGN(uv_meta_stride * - uv_meta_scanlines, 4096); - - size = y_ubwc_plane + uv_ubwc_plane + y_meta_plane + - uv_meta_plane; - size = MSM_MEDIA_ALIGN(size, 4096); - break; - case COLOR_FMT_RGBA8888: - rgb_plane = MSM_MEDIA_ALIGN(rgb_stride * rgb_scanlines, 4096); - size = rgb_plane; - size = MSM_MEDIA_ALIGN(size, 4096); - break; - case COLOR_FMT_RGBA8888_UBWC: - case COLOR_FMT_RGBA1010102_UBWC: - case COLOR_FMT_RGB565_UBWC: - rgb_ubwc_plane = MSM_MEDIA_ALIGN(rgb_stride * rgb_scanlines, - 4096); - rgb_meta_stride = VENUS_RGB_META_STRIDE(color_fmt, width); - rgb_meta_scanlines = VENUS_RGB_META_SCANLINES(color_fmt, - height); - rgb_meta_plane = MSM_MEDIA_ALIGN(rgb_meta_stride * - rgb_meta_scanlines, 4096); - size = rgb_ubwc_plane + rgb_meta_plane; - size = MSM_MEDIA_ALIGN(size, 4096); - break; - default: - break; - } -invalid_input: - return size; -} - -static inline unsigned int VENUS_VIEW2_OFFSET( - int color_fmt, int width, int height) -{ - unsigned int offset = 0; - unsigned int y_plane, uv_plane, y_stride, - uv_stride, y_sclines, uv_sclines; - if (!width || !height) - goto invalid_input; - - y_stride = VENUS_Y_STRIDE(color_fmt, width); - uv_stride = VENUS_UV_STRIDE(color_fmt, width); - y_sclines = VENUS_Y_SCANLINES(color_fmt, height); - uv_sclines = VENUS_UV_SCANLINES(color_fmt, height); - switch (color_fmt) { - case COLOR_FMT_NV12_MVTB: - y_plane = y_stride * y_sclines; - uv_plane = uv_stride * uv_sclines; - offset = y_plane + uv_plane; - break; - default: - break; - } -invalid_input: - return offset; -} - -#endif diff --git a/third_party/linux/include/msmb_camera.h b/third_party/linux/include/msmb_camera.h deleted file mode 100644 index f4c4b3e183..0000000000 --- a/third_party/linux/include/msmb_camera.h +++ /dev/null @@ -1,220 +0,0 @@ -#ifndef __LINUX_MSMB_CAMERA_H -#define __LINUX_MSMB_CAMERA_H - -#include -#include -#include - -#define MSM_CAM_LOGSYNC_FILE_NAME "logsync" -#define MSM_CAM_LOGSYNC_FILE_BASEDIR "camera" - -#define MSM_CAM_V4L2_IOCTL_NOTIFY \ - _IOW('V', BASE_VIDIOC_PRIVATE + 30, struct msm_v4l2_event_data) - -#define MSM_CAM_V4L2_IOCTL_NOTIFY_META \ - _IOW('V', BASE_VIDIOC_PRIVATE + 31, struct msm_v4l2_event_data) - -#define MSM_CAM_V4L2_IOCTL_CMD_ACK \ - _IOW('V', BASE_VIDIOC_PRIVATE + 32, struct msm_v4l2_event_data) - -#define MSM_CAM_V4L2_IOCTL_NOTIFY_ERROR \ - _IOW('V', BASE_VIDIOC_PRIVATE + 33, struct msm_v4l2_event_data) - -#define MSM_CAM_V4L2_IOCTL_NOTIFY_DEBUG \ - _IOW('V', BASE_VIDIOC_PRIVATE + 34, struct msm_v4l2_event_data) - -#ifdef CONFIG_COMPAT -#define MSM_CAM_V4L2_IOCTL_NOTIFY32 \ - _IOW('V', BASE_VIDIOC_PRIVATE + 30, struct v4l2_event32) - -#define MSM_CAM_V4L2_IOCTL_NOTIFY_META32 \ - _IOW('V', BASE_VIDIOC_PRIVATE + 31, struct v4l2_event32) - -#define MSM_CAM_V4L2_IOCTL_CMD_ACK32 \ - _IOW('V', BASE_VIDIOC_PRIVATE + 32, struct v4l2_event32) - -#define MSM_CAM_V4L2_IOCTL_NOTIFY_ERROR32 \ - _IOW('V', BASE_VIDIOC_PRIVATE + 33, struct v4l2_event32) - -#define MSM_CAM_V4L2_IOCTL_NOTIFY_DEBUG32 \ - _IOW('V', BASE_VIDIOC_PRIVATE + 34, struct v4l2_event32) - -#endif - -#define QCAMERA_DEVICE_GROUP_ID 1 -#define QCAMERA_VNODE_GROUP_ID 2 -#define MSM_CAMERA_NAME "msm_camera" -#define MSM_CONFIGURATION_NAME "msm_config" - -#define MSM_CAMERA_SUBDEV_CSIPHY 0 -#define MSM_CAMERA_SUBDEV_CSID 1 -#define MSM_CAMERA_SUBDEV_ISPIF 2 -#define MSM_CAMERA_SUBDEV_VFE 3 -#define MSM_CAMERA_SUBDEV_AXI 4 -#define MSM_CAMERA_SUBDEV_VPE 5 -#define MSM_CAMERA_SUBDEV_SENSOR 6 -#define MSM_CAMERA_SUBDEV_ACTUATOR 7 -#define MSM_CAMERA_SUBDEV_EEPROM 8 -#define MSM_CAMERA_SUBDEV_CPP 9 -#define MSM_CAMERA_SUBDEV_CCI 10 -#define MSM_CAMERA_SUBDEV_LED_FLASH 11 -#define MSM_CAMERA_SUBDEV_STROBE_FLASH 12 -#define MSM_CAMERA_SUBDEV_BUF_MNGR 13 -#define MSM_CAMERA_SUBDEV_SENSOR_INIT 14 -#define MSM_CAMERA_SUBDEV_OIS 15 -#define MSM_CAMERA_SUBDEV_FLASH 16 -#define MSM_CAMERA_SUBDEV_EXT 17 - -#define MSM_MAX_CAMERA_SENSORS 5 - -/* The below macro is defined to put an upper limit on maximum - * number of buffer requested per stream. In case of extremely - * large value for number of buffer due to data structure corruption - * we return error to avoid integer overflow. Group processing - * can have max of 9 groups of 8 bufs each. This value may be - * configured in future*/ -#define MSM_CAMERA_MAX_STREAM_BUF 72 - -/* Max batch size of processing */ -#define MSM_CAMERA_MAX_USER_BUFF_CNT 16 - -/* featur base */ -#define MSM_CAMERA_FEATURE_BASE 0x00010000 -#define MSM_CAMERA_FEATURE_SHUTDOWN (MSM_CAMERA_FEATURE_BASE + 1) - -#define MSM_CAMERA_STATUS_BASE 0x00020000 -#define MSM_CAMERA_STATUS_FAIL (MSM_CAMERA_STATUS_BASE + 1) -#define MSM_CAMERA_STATUS_SUCCESS (MSM_CAMERA_STATUS_BASE + 2) - -/* event type */ -#define MSM_CAMERA_V4L2_EVENT_TYPE (V4L2_EVENT_PRIVATE_START + 0x00002000) - -/* event id */ -#define MSM_CAMERA_EVENT_MIN 0 -#define MSM_CAMERA_NEW_SESSION (MSM_CAMERA_EVENT_MIN + 1) -#define MSM_CAMERA_DEL_SESSION (MSM_CAMERA_EVENT_MIN + 2) -#define MSM_CAMERA_SET_PARM (MSM_CAMERA_EVENT_MIN + 3) -#define MSM_CAMERA_GET_PARM (MSM_CAMERA_EVENT_MIN + 4) -#define MSM_CAMERA_MAPPING_CFG (MSM_CAMERA_EVENT_MIN + 5) -#define MSM_CAMERA_MAPPING_SES (MSM_CAMERA_EVENT_MIN + 6) -#define MSM_CAMERA_MSM_NOTIFY (MSM_CAMERA_EVENT_MIN + 7) -#define MSM_CAMERA_EVENT_MAX (MSM_CAMERA_EVENT_MIN + 8) - -/* data.command */ -#define MSM_CAMERA_PRIV_S_CROP (V4L2_CID_PRIVATE_BASE + 1) -#define MSM_CAMERA_PRIV_G_CROP (V4L2_CID_PRIVATE_BASE + 2) -#define MSM_CAMERA_PRIV_G_FMT (V4L2_CID_PRIVATE_BASE + 3) -#define MSM_CAMERA_PRIV_S_FMT (V4L2_CID_PRIVATE_BASE + 4) -#define MSM_CAMERA_PRIV_TRY_FMT (V4L2_CID_PRIVATE_BASE + 5) -#define MSM_CAMERA_PRIV_METADATA (V4L2_CID_PRIVATE_BASE + 6) -#define MSM_CAMERA_PRIV_QUERY_CAP (V4L2_CID_PRIVATE_BASE + 7) -#define MSM_CAMERA_PRIV_STREAM_ON (V4L2_CID_PRIVATE_BASE + 8) -#define MSM_CAMERA_PRIV_STREAM_OFF (V4L2_CID_PRIVATE_BASE + 9) -#define MSM_CAMERA_PRIV_NEW_STREAM (V4L2_CID_PRIVATE_BASE + 10) -#define MSM_CAMERA_PRIV_DEL_STREAM (V4L2_CID_PRIVATE_BASE + 11) -#define MSM_CAMERA_PRIV_SHUTDOWN (V4L2_CID_PRIVATE_BASE + 12) -#define MSM_CAMERA_PRIV_STREAM_INFO_SYNC \ - (V4L2_CID_PRIVATE_BASE + 13) -#define MSM_CAMERA_PRIV_G_SESSION_ID (V4L2_CID_PRIVATE_BASE + 14) -#define MSM_CAMERA_PRIV_CMD_MAX 20 - -/* data.status - success */ -#define MSM_CAMERA_CMD_SUCESS 0x00000001 -#define MSM_CAMERA_BUF_MAP_SUCESS 0x00000002 - -/* data.status - error */ -#define MSM_CAMERA_ERR_EVT_BASE 0x00010000 -#define MSM_CAMERA_ERR_CMD_FAIL (MSM_CAMERA_ERR_EVT_BASE + 1) -#define MSM_CAMERA_ERR_MAPPING (MSM_CAMERA_ERR_EVT_BASE + 2) -#define MSM_CAMERA_ERR_DEVICE_BUSY (MSM_CAMERA_ERR_EVT_BASE + 3) - -/* The msm_v4l2_event_data structure should match the - * v4l2_event.u.data field. - * should not exceed 16 elements */ -struct msm_v4l2_event_data { - /*word 0*/ - unsigned int command; - /*word 1*/ - unsigned int status; - /*word 2*/ - unsigned int session_id; - /*word 3*/ - unsigned int stream_id; - /*word 4*/ - unsigned int map_op; - /*word 5*/ - unsigned int map_buf_idx; - /*word 6*/ - unsigned int notify; - /*word 7*/ - unsigned int arg_value; - /*word 8*/ - unsigned int ret_value; - /*word 9*/ - unsigned int v4l2_event_type; - /*word 10*/ - unsigned int v4l2_event_id; - /*word 11*/ - unsigned int handle; - /*word 12*/ - unsigned int nop6; - /*word 13*/ - unsigned int nop7; - /*word 14*/ - unsigned int nop8; - /*word 15*/ - unsigned int nop9; -}; - -/* map to v4l2_format.fmt.raw_data */ -struct msm_v4l2_format_data { - enum v4l2_buf_type type; - unsigned int width; - unsigned int height; - unsigned int pixelformat; /* FOURCC */ - unsigned char num_planes; - unsigned int plane_sizes[VIDEO_MAX_PLANES]; -}; - -/* MSM Four-character-code (FOURCC) */ -#define msm_v4l2_fourcc(a, b, c, d)\ - ((__u32)(a) | ((__u32)(b) << 8) | ((__u32)(c) << 16) |\ - ((__u32)(d) << 24)) - -/* Composite stats */ -#define MSM_V4L2_PIX_FMT_STATS_COMB v4l2_fourcc('S', 'T', 'C', 'M') -/* AEC stats */ -#define MSM_V4L2_PIX_FMT_STATS_AE v4l2_fourcc('S', 'T', 'A', 'E') -/* AF stats */ -#define MSM_V4L2_PIX_FMT_STATS_AF v4l2_fourcc('S', 'T', 'A', 'F') -/* AWB stats */ -#define MSM_V4L2_PIX_FMT_STATS_AWB v4l2_fourcc('S', 'T', 'W', 'B') -/* IHIST stats */ -#define MSM_V4L2_PIX_FMT_STATS_IHST v4l2_fourcc('I', 'H', 'S', 'T') -/* Column count stats */ -#define MSM_V4L2_PIX_FMT_STATS_CS v4l2_fourcc('S', 'T', 'C', 'S') -/* Row count stats */ -#define MSM_V4L2_PIX_FMT_STATS_RS v4l2_fourcc('S', 'T', 'R', 'S') -/* Bayer Grid stats */ -#define MSM_V4L2_PIX_FMT_STATS_BG v4l2_fourcc('S', 'T', 'B', 'G') -/* Bayer focus stats */ -#define MSM_V4L2_PIX_FMT_STATS_BF v4l2_fourcc('S', 'T', 'B', 'F') -/* Bayer hist stats */ -#define MSM_V4L2_PIX_FMT_STATS_BHST v4l2_fourcc('B', 'H', 'S', 'T') - -enum smmu_attach_mode { - NON_SECURE_MODE = 0x01, - SECURE_MODE = 0x02, - MAX_PROTECTION_MODE = 0x03, -}; - -struct msm_camera_smmu_attach_type { - enum smmu_attach_mode attach; -}; - -struct msm_camera_user_buf_cont_t { - unsigned int buf_cnt; - unsigned int buf_idx[MSM_CAMERA_MAX_USER_BUFF_CNT]; -}; - -#endif /* __LINUX_MSMB_CAMERA_H */ diff --git a/third_party/linux/include/msmb_isp.h b/third_party/linux/include/msmb_isp.h deleted file mode 100644 index 35589e050a..0000000000 --- a/third_party/linux/include/msmb_isp.h +++ /dev/null @@ -1,880 +0,0 @@ -#ifndef __MSMB_ISP__ -#define __MSMB_ISP__ - -#include - -#define MAX_PLANES_PER_STREAM 3 -#define MAX_NUM_STREAM 7 - -#define ISP_VERSION_47 47 -#define ISP_VERSION_46 46 -#define ISP_VERSION_44 44 -#define ISP_VERSION_40 40 -#define ISP_VERSION_32 32 -#define ISP_NATIVE_BUF_BIT (0x10000 << 0) -#define ISP0_BIT (0x10000 << 1) -#define ISP1_BIT (0x10000 << 2) -#define ISP_META_CHANNEL_BIT (0x10000 << 3) -#define ISP_SCRATCH_BUF_BIT (0x10000 << 4) -#define ISP_OFFLINE_STATS_BIT (0x10000 << 5) -#define ISP_STATS_STREAM_BIT 0x80000000 - -struct msm_vfe_cfg_cmd_list; - -enum ISP_START_PIXEL_PATTERN { - ISP_BAYER_RGRGRG, - ISP_BAYER_GRGRGR, - ISP_BAYER_BGBGBG, - ISP_BAYER_GBGBGB, - ISP_YUV_YCbYCr, - ISP_YUV_YCrYCb, - ISP_YUV_CbYCrY, - ISP_YUV_CrYCbY, - ISP_PIX_PATTERN_MAX -}; - -enum msm_vfe_plane_fmt { - Y_PLANE, - CB_PLANE, - CR_PLANE, - CRCB_PLANE, - CBCR_PLANE, - VFE_PLANE_FMT_MAX -}; - -enum msm_vfe_input_src { - VFE_PIX_0, - VFE_RAW_0, - VFE_RAW_1, - VFE_RAW_2, - VFE_SRC_MAX, -}; - -enum msm_vfe_axi_stream_src { - PIX_ENCODER, - PIX_VIEWFINDER, - PIX_VIDEO, - CAMIF_RAW, - IDEAL_RAW, - RDI_INTF_0, - RDI_INTF_1, - RDI_INTF_2, - VFE_AXI_SRC_MAX -}; - -enum msm_vfe_frame_skip_pattern { - NO_SKIP, - EVERY_2FRAME, - EVERY_3FRAME, - EVERY_4FRAME, - EVERY_5FRAME, - EVERY_6FRAME, - EVERY_7FRAME, - EVERY_8FRAME, - EVERY_16FRAME, - EVERY_32FRAME, - SKIP_ALL, - SKIP_RANGE, - MAX_SKIP, -}; - -/* - * Define an unused period. When this period is set it means that the stream is - * stopped(i.e the pattern is 0). We don't track the current pattern, just the - * period defines what the pattern is, if period is this then pattern is 0 else - * pattern is 1 - */ -#define MSM_VFE_STREAM_STOP_PERIOD 15 - -enum msm_isp_stats_type { - MSM_ISP_STATS_AEC, /* legacy based AEC */ - MSM_ISP_STATS_AF, /* legacy based AF */ - MSM_ISP_STATS_AWB, /* legacy based AWB */ - MSM_ISP_STATS_RS, /* legacy based RS */ - MSM_ISP_STATS_CS, /* legacy based CS */ - MSM_ISP_STATS_IHIST, /* legacy based HIST */ - MSM_ISP_STATS_SKIN, /* legacy based SKIN */ - MSM_ISP_STATS_BG, /* Bayer Grids */ - MSM_ISP_STATS_BF, /* Bayer Focus */ - MSM_ISP_STATS_BE, /* Bayer Exposure*/ - MSM_ISP_STATS_BHIST, /* Bayer Hist */ - MSM_ISP_STATS_BF_SCALE, /* Bayer Focus scale */ - MSM_ISP_STATS_HDR_BE, /* HDR Bayer Exposure */ - MSM_ISP_STATS_HDR_BHIST, /* HDR Bayer Hist */ - MSM_ISP_STATS_AEC_BG, /* AEC BG */ - MSM_ISP_STATS_MAX /* MAX */ -}; - -/* - * @stats_type_mask: Stats type mask (enum msm_isp_stats_type). - * @stream_src_mask: Stream src mask (enum msm_vfe_axi_stream_src) - * @skip_mode: skip pattern, if skip mode is range only then min/max is used - * @min_frame_id: minimum frame id (valid only if skip_mode = RANGE) - * @max_frame_id: maximum frame id (valid only if skip_mode = RANGE) -*/ -struct msm_isp_sw_framskip { - uint32_t stats_type_mask; - uint32_t stream_src_mask; - enum msm_vfe_frame_skip_pattern skip_mode; - uint32_t min_frame_id; - uint32_t max_frame_id; -}; - -enum msm_vfe_testgen_color_pattern { - COLOR_BAR_8_COLOR, - UNICOLOR_WHITE, - UNICOLOR_YELLOW, - UNICOLOR_CYAN, - UNICOLOR_GREEN, - UNICOLOR_MAGENTA, - UNICOLOR_RED, - UNICOLOR_BLUE, - UNICOLOR_BLACK, - MAX_COLOR, -}; - -enum msm_vfe_camif_input { - CAMIF_DISABLED, - CAMIF_PAD_REG_INPUT, - CAMIF_MIDDI_INPUT, - CAMIF_MIPI_INPUT, -}; - -struct msm_vfe_fetch_engine_cfg { - uint32_t input_format; - uint32_t buf_width; - uint32_t buf_height; - uint32_t fetch_width; - uint32_t fetch_height; - uint32_t x_offset; - uint32_t y_offset; - uint32_t buf_stride; -}; - -enum msm_vfe_camif_output_format { - CAMIF_QCOM_RAW, - CAMIF_MIPI_RAW, - CAMIF_PLAIN_8, - CAMIF_PLAIN_16, - CAMIF_MAX_FORMAT, -}; - -/* - * Camif output general configuration - */ -struct msm_vfe_camif_subsample_cfg { - uint32_t irq_subsample_period; - uint32_t irq_subsample_pattern; - uint32_t sof_counter_step; - uint32_t pixel_skip; - uint32_t line_skip; - uint32_t first_line; - uint32_t last_line; - uint32_t first_pixel; - uint32_t last_pixel; - enum msm_vfe_camif_output_format output_format; -}; - -/* - * Camif frame and window configuration - */ -struct msm_vfe_camif_cfg { - uint32_t lines_per_frame; - uint32_t pixels_per_line; - uint32_t first_pixel; - uint32_t last_pixel; - uint32_t first_line; - uint32_t last_line; - uint32_t epoch_line0; - uint32_t epoch_line1; - uint32_t is_split; - enum msm_vfe_camif_input camif_input; - struct msm_vfe_camif_subsample_cfg subsample_cfg; -}; - -struct msm_vfe_testgen_cfg { - uint32_t lines_per_frame; - uint32_t pixels_per_line; - uint32_t v_blank; - uint32_t h_blank; - enum ISP_START_PIXEL_PATTERN pixel_bayer_pattern; - uint32_t rotate_period; - enum msm_vfe_testgen_color_pattern color_bar_pattern; - uint32_t burst_num_frame; -}; - -enum msm_vfe_inputmux { - CAMIF, - TESTGEN, - EXTERNAL_READ, -}; - -enum msm_vfe_stats_composite_group { - STATS_COMPOSITE_GRP_NONE, - STATS_COMPOSITE_GRP_1, - STATS_COMPOSITE_GRP_2, - STATS_COMPOSITE_GRP_MAX, -}; - -enum msm_vfe_hvx_streaming_cmd { - HVX_DISABLE, - HVX_ONE_WAY, - HVX_ROUND_TRIP -}; - -struct msm_vfe_pix_cfg { - struct msm_vfe_camif_cfg camif_cfg; - struct msm_vfe_testgen_cfg testgen_cfg; - struct msm_vfe_fetch_engine_cfg fetch_engine_cfg; - enum msm_vfe_inputmux input_mux; - enum ISP_START_PIXEL_PATTERN pixel_pattern; - uint32_t input_format; - enum msm_vfe_hvx_streaming_cmd hvx_cmd; - uint32_t is_split; -}; - -struct msm_vfe_rdi_cfg { - uint8_t cid; - uint8_t frame_based; -}; - -struct msm_vfe_input_cfg { - union { - struct msm_vfe_pix_cfg pix_cfg; - struct msm_vfe_rdi_cfg rdi_cfg; - } d; - enum msm_vfe_input_src input_src; - uint32_t input_pix_clk; -}; - -struct msm_vfe_fetch_eng_start { - uint32_t session_id; - uint32_t stream_id; - uint32_t buf_idx; - uint8_t offline_mode; - uint32_t fd; - uint32_t buf_addr; - uint32_t frame_id; -}; - -struct msm_vfe_axi_plane_cfg { - uint32_t output_width; /*Include padding*/ - uint32_t output_height; - uint32_t output_stride; - uint32_t output_scan_lines; - uint32_t output_plane_format; /*Y/Cb/Cr/CbCr*/ - uint32_t plane_addr_offset; - uint8_t csid_src; /*RDI 0-2*/ - uint8_t rdi_cid;/*CID 1-16*/ -}; - -enum msm_stream_memory_input_t { - MEMORY_INPUT_DISABLED, - MEMORY_INPUT_ENABLED -}; - -struct msm_vfe_axi_stream_request_cmd { - uint32_t session_id; - uint32_t stream_id; - uint32_t vt_enable; - uint32_t output_format;/*Planar/RAW/Misc*/ - enum msm_vfe_axi_stream_src stream_src; /*CAMIF/IDEAL/RDIs*/ - struct msm_vfe_axi_plane_cfg plane_cfg[MAX_PLANES_PER_STREAM]; - - uint32_t burst_count; - uint32_t hfr_mode; - uint8_t frame_base; - - uint32_t init_frame_drop; /*MAX 31 Frames*/ - enum msm_vfe_frame_skip_pattern frame_skip_pattern; - uint8_t buf_divert; /* if TRUE no vb2 buf done. */ - /*Return values*/ - uint32_t axi_stream_handle; - uint32_t controllable_output; - uint32_t burst_len; - /* Flag indicating memory input stream */ - enum msm_stream_memory_input_t memory_input; -}; - -struct msm_vfe_axi_stream_release_cmd { - uint32_t stream_handle; -}; - -enum msm_vfe_axi_stream_cmd { - STOP_STREAM, - START_STREAM, - STOP_IMMEDIATELY, -}; - -struct msm_vfe_axi_stream_cfg_cmd { - uint8_t num_streams; - uint32_t stream_handle[VFE_AXI_SRC_MAX]; - enum msm_vfe_axi_stream_cmd cmd; - uint8_t sync_frame_id_src; -}; - -enum msm_vfe_axi_stream_update_type { - ENABLE_STREAM_BUF_DIVERT, - DISABLE_STREAM_BUF_DIVERT, - UPDATE_STREAM_FRAMEDROP_PATTERN, - UPDATE_STREAM_STATS_FRAMEDROP_PATTERN, - UPDATE_STREAM_AXI_CONFIG, - UPDATE_STREAM_REQUEST_FRAMES, - UPDATE_STREAM_ADD_BUFQ, - UPDATE_STREAM_REMOVE_BUFQ, - UPDATE_STREAM_SW_FRAME_DROP, -}; - -enum msm_vfe_iommu_type { - IOMMU_ATTACH, - IOMMU_DETACH, -}; - -enum msm_vfe_buff_queue_id { - VFE_BUF_QUEUE_DEFAULT, - VFE_BUF_QUEUE_SHARED, - VFE_BUF_QUEUE_MAX, -}; - -struct msm_vfe_axi_stream_cfg_update_info { - uint32_t stream_handle; - uint32_t output_format; - uint32_t user_stream_id; - uint32_t frame_id; - enum msm_vfe_frame_skip_pattern skip_pattern; - struct msm_vfe_axi_plane_cfg plane_cfg[MAX_PLANES_PER_STREAM]; - struct msm_isp_sw_framskip sw_skip_info; -}; - -struct msm_vfe_axi_halt_cmd { - uint32_t stop_camif; - uint32_t overflow_detected; - uint32_t blocking_halt; -}; - -struct msm_vfe_axi_reset_cmd { - uint32_t blocking; - uint32_t frame_id; -}; - -struct msm_vfe_axi_restart_cmd { - uint32_t enable_camif; -}; - -struct msm_vfe_axi_stream_update_cmd { - uint32_t num_streams; - enum msm_vfe_axi_stream_update_type update_type; - struct msm_vfe_axi_stream_cfg_update_info - update_info[MSM_ISP_STATS_MAX]; -}; - -struct msm_vfe_smmu_attach_cmd { - uint32_t security_mode; - uint32_t iommu_attach_mode; -}; - -struct msm_vfe_stats_stream_request_cmd { - uint32_t session_id; - uint32_t stream_id; - enum msm_isp_stats_type stats_type; - uint32_t composite_flag; - uint32_t framedrop_pattern; - uint32_t init_frame_drop; /*MAX 31 Frames*/ - uint32_t irq_subsample_pattern; - uint32_t buffer_offset; - uint32_t stream_handle; -}; - -struct msm_vfe_stats_stream_release_cmd { - uint32_t stream_handle; -}; -struct msm_vfe_stats_stream_cfg_cmd { - uint8_t num_streams; - uint32_t stream_handle[MSM_ISP_STATS_MAX]; - uint8_t enable; - uint32_t stats_burst_len; -}; - -enum msm_vfe_reg_cfg_type { - VFE_WRITE, - VFE_WRITE_MB, - VFE_READ, - VFE_CFG_MASK, - VFE_WRITE_DMI_16BIT, - VFE_WRITE_DMI_32BIT, - VFE_WRITE_DMI_64BIT, - VFE_READ_DMI_16BIT, - VFE_READ_DMI_32BIT, - VFE_READ_DMI_64BIT, - GET_MAX_CLK_RATE, - GET_CLK_RATES, - GET_ISP_ID, - VFE_HW_UPDATE_LOCK, - VFE_HW_UPDATE_UNLOCK, - SET_WM_UB_SIZE, - SET_UB_POLICY, -}; - -struct msm_vfe_cfg_cmd2 { - uint16_t num_cfg; - uint16_t cmd_len; - void __user *cfg_data; - void __user *cfg_cmd; -}; - -struct msm_vfe_cfg_cmd_list { - struct msm_vfe_cfg_cmd2 cfg_cmd; - struct msm_vfe_cfg_cmd_list *next; - uint32_t next_size; -}; - -struct msm_vfe_reg_rw_info { - uint32_t reg_offset; - uint32_t cmd_data_offset; - uint32_t len; -}; - -struct msm_vfe_reg_mask_info { - uint32_t reg_offset; - uint32_t mask; - uint32_t val; -}; - -struct msm_vfe_reg_dmi_info { - uint32_t hi_tbl_offset; /*Optional*/ - uint32_t lo_tbl_offset; /*Required*/ - uint32_t len; -}; - -struct msm_vfe_reg_cfg_cmd { - union { - struct msm_vfe_reg_rw_info rw_info; - struct msm_vfe_reg_mask_info mask_info; - struct msm_vfe_reg_dmi_info dmi_info; - } u; - - enum msm_vfe_reg_cfg_type cmd_type; -}; - -enum vfe_sd_type { - VFE_SD_0 = 0, - VFE_SD_1, - VFE_SD_COMMON, - VFE_SD_MAX, -}; - -/* When you change the value below, check for the sof event_data size. - * V4l2 limits payload to 64 bytes */ -#define MS_NUM_SLAVE_MAX 1 - -/* Usecases when 2 HW need to be related or synced */ -enum msm_vfe_dual_hw_type { - DUAL_NONE = 0, - DUAL_HW_VFE_SPLIT = 1, - DUAL_HW_MASTER_SLAVE = 2, -}; - -/* Type for 2 INTF when used in Master-Slave mode */ -enum msm_vfe_dual_hw_ms_type { - MS_TYPE_NONE, - MS_TYPE_MASTER, - MS_TYPE_SLAVE, -}; - -struct msm_isp_set_dual_hw_ms_cmd { - uint8_t num_src; - /* Each session can be only one type but multiple intf if YUV cam */ - enum msm_vfe_dual_hw_ms_type dual_hw_ms_type; - /* Primary intf is mostly associated with preview. - * This primary intf SOF frame_id and timestamp is tracked - * and used to calculate delta */ - enum msm_vfe_input_src primary_intf; - /* input_src array indicates other input INTF that may be Master/Slave. - * For these additional intf, frame_id and timestamp are not saved. - * However, if these are slaves then they will still get their - * frame_id from Master */ - enum msm_vfe_input_src input_src[VFE_SRC_MAX]; - uint32_t sof_delta_threshold; /* In milliseconds. Sent for Master */ -}; - -enum msm_isp_buf_type { - ISP_PRIVATE_BUF, - ISP_SHARE_BUF, - MAX_ISP_BUF_TYPE, -}; - -struct msm_isp_unmap_buf_req { - uint32_t fd; -}; - -struct msm_isp_buf_request { - uint32_t session_id; - uint32_t stream_id; - uint8_t num_buf; - uint32_t handle; - enum msm_isp_buf_type buf_type; -}; - -struct msm_isp_qbuf_plane { - uint32_t addr; - uint32_t offset; - uint32_t length; -}; - -struct msm_isp_qbuf_buffer { - struct msm_isp_qbuf_plane planes[MAX_PLANES_PER_STREAM]; - uint32_t num_planes; -}; - -struct msm_isp_qbuf_info { - uint32_t handle; - int32_t buf_idx; - /*Only used for prepare buffer*/ - struct msm_isp_qbuf_buffer buffer; - /*Only used for diverted buffer*/ - uint32_t dirty_buf; -}; - -struct msm_isp_clk_rates { - uint32_t svs_rate; - uint32_t nominal_rate; - uint32_t high_rate; -}; - -struct msm_vfe_axi_src_state { - enum msm_vfe_input_src input_src; - uint32_t src_active; - uint32_t src_frame_id; -}; - -enum msm_isp_event_mask_index { - ISP_EVENT_MASK_INDEX_STATS_NOTIFY = 0, - ISP_EVENT_MASK_INDEX_ERROR = 1, - ISP_EVENT_MASK_INDEX_IOMMU_P_FAULT = 2, - ISP_EVENT_MASK_INDEX_STREAM_UPDATE_DONE = 3, - ISP_EVENT_MASK_INDEX_REG_UPDATE = 4, - ISP_EVENT_MASK_INDEX_SOF = 5, - ISP_EVENT_MASK_INDEX_BUF_DIVERT = 6, - ISP_EVENT_MASK_INDEX_COMP_STATS_NOTIFY = 7, - ISP_EVENT_MASK_INDEX_MASK_FE_READ_DONE = 8, - ISP_EVENT_MASK_INDEX_BUF_DONE = 9, - ISP_EVENT_MASK_INDEX_REG_UPDATE_MISSING = 10, - ISP_EVENT_MASK_INDEX_PING_PONG_MISMATCH = 11, - ISP_EVENT_MASK_INDEX_BUF_FATAL_ERROR = 12, -}; - - -#define ISP_EVENT_SUBS_MASK_NONE 0 - -#define ISP_EVENT_SUBS_MASK_STATS_NOTIFY \ - (1 << ISP_EVENT_MASK_INDEX_STATS_NOTIFY) - -#define ISP_EVENT_SUBS_MASK_ERROR \ - (1 << ISP_EVENT_MASK_INDEX_ERROR) - -#define ISP_EVENT_SUBS_MASK_IOMMU_P_FAULT \ - (1 << ISP_EVENT_MASK_INDEX_IOMMU_P_FAULT) - -#define ISP_EVENT_SUBS_MASK_STREAM_UPDATE_DONE \ - (1 << ISP_EVENT_MASK_INDEX_STREAM_UPDATE_DONE) - -#define ISP_EVENT_SUBS_MASK_REG_UPDATE \ - (1 << ISP_EVENT_MASK_INDEX_REG_UPDATE) - -#define ISP_EVENT_SUBS_MASK_SOF \ - (1 << ISP_EVENT_MASK_INDEX_SOF) - -#define ISP_EVENT_SUBS_MASK_BUF_DIVERT \ - (1 << ISP_EVENT_MASK_INDEX_BUF_DIVERT) - -#define ISP_EVENT_SUBS_MASK_COMP_STATS_NOTIFY \ - (1 << ISP_EVENT_MASK_INDEX_COMP_STATS_NOTIFY) - -#define ISP_EVENT_SUBS_MASK_FE_READ_DONE \ - (1 << ISP_EVENT_MASK_INDEX_MASK_FE_READ_DONE) - -#define ISP_EVENT_SUBS_MASK_BUF_DONE \ - (1 << ISP_EVENT_MASK_INDEX_BUF_DONE) - -#define ISP_EVENT_SUBS_MASK_REG_UPDATE_MISSING \ - (1 << ISP_EVENT_MASK_INDEX_REG_UPDATE_MISSING) - -#define ISP_EVENT_SUBS_MASK_PING_PONG_MISMATCH \ - (1 << ISP_EVENT_MASK_INDEX_PING_PONG_MISMATCH) - -#define ISP_EVENT_SUBS_MASK_BUF_FATAL_ERROR \ - (1 << ISP_EVENT_MASK_INDEX_BUF_FATAL_ERROR) - -enum msm_isp_event_idx { - ISP_REG_UPDATE = 0, - ISP_EPOCH_0 = 1, - ISP_EPOCH_1 = 2, - ISP_START_ACK = 3, - ISP_STOP_ACK = 4, - ISP_IRQ_VIOLATION = 5, - ISP_STATS_OVERFLOW = 6, - ISP_BUF_DONE = 7, - ISP_FE_RD_DONE = 8, - ISP_IOMMU_P_FAULT = 9, - ISP_ERROR = 10, - ISP_HW_FATAL_ERROR = 11, - ISP_PING_PONG_MISMATCH = 12, - ISP_REG_UPDATE_MISSING = 13, - ISP_BUF_FATAL_ERROR = 14, - ISP_EVENT_MAX = 15 -}; - -#define ISP_EVENT_OFFSET 8 -#define ISP_EVENT_BASE (V4L2_EVENT_PRIVATE_START) -#define ISP_BUF_EVENT_BASE (ISP_EVENT_BASE + (1 << ISP_EVENT_OFFSET)) -#define ISP_STATS_EVENT_BASE (ISP_EVENT_BASE + (2 << ISP_EVENT_OFFSET)) -#define ISP_CAMIF_EVENT_BASE (ISP_EVENT_BASE + (3 << ISP_EVENT_OFFSET)) -#define ISP_STREAM_EVENT_BASE (ISP_EVENT_BASE + (4 << ISP_EVENT_OFFSET)) -#define ISP_EVENT_REG_UPDATE (ISP_EVENT_BASE + ISP_REG_UPDATE) -#define ISP_EVENT_EPOCH_0 (ISP_EVENT_BASE + ISP_EPOCH_0) -#define ISP_EVENT_EPOCH_1 (ISP_EVENT_BASE + ISP_EPOCH_1) -#define ISP_EVENT_START_ACK (ISP_EVENT_BASE + ISP_START_ACK) -#define ISP_EVENT_STOP_ACK (ISP_EVENT_BASE + ISP_STOP_ACK) -#define ISP_EVENT_IRQ_VIOLATION (ISP_EVENT_BASE + ISP_IRQ_VIOLATION) -#define ISP_EVENT_STATS_OVERFLOW (ISP_EVENT_BASE + ISP_STATS_OVERFLOW) -#define ISP_EVENT_ERROR (ISP_EVENT_BASE + ISP_ERROR) -#define ISP_EVENT_SOF (ISP_CAMIF_EVENT_BASE) -#define ISP_EVENT_EOF (ISP_CAMIF_EVENT_BASE + 1) -#define ISP_EVENT_BUF_DONE (ISP_EVENT_BASE + ISP_BUF_DONE) -#define ISP_EVENT_BUF_DIVERT (ISP_BUF_EVENT_BASE) -#define ISP_EVENT_STATS_NOTIFY (ISP_STATS_EVENT_BASE) -#define ISP_EVENT_COMP_STATS_NOTIFY (ISP_EVENT_STATS_NOTIFY + MSM_ISP_STATS_MAX) -#define ISP_EVENT_FE_READ_DONE (ISP_EVENT_BASE + ISP_FE_RD_DONE) -#define ISP_EVENT_IOMMU_P_FAULT (ISP_EVENT_BASE + ISP_IOMMU_P_FAULT) -#define ISP_EVENT_HW_FATAL_ERROR (ISP_EVENT_BASE + ISP_HW_FATAL_ERROR) -#define ISP_EVENT_PING_PONG_MISMATCH (ISP_EVENT_BASE + ISP_PING_PONG_MISMATCH) -#define ISP_EVENT_REG_UPDATE_MISSING (ISP_EVENT_BASE + ISP_REG_UPDATE_MISSING) -#define ISP_EVENT_BUF_FATAL_ERROR (ISP_EVENT_BASE + ISP_BUF_FATAL_ERROR) -#define ISP_EVENT_STREAM_UPDATE_DONE (ISP_STREAM_EVENT_BASE) - -/* The msm_v4l2_event_data structure should match the - * v4l2_event.u.data field. - * should not exceed 64 bytes */ - -struct msm_isp_buf_event { - uint32_t session_id; - uint32_t stream_id; - uint32_t handle; - uint32_t output_format; - int8_t buf_idx; -}; -struct msm_isp_fetch_eng_event { - uint32_t session_id; - uint32_t stream_id; - uint32_t handle; - uint32_t fd; - int8_t buf_idx; - int8_t offline_mode; -}; -struct msm_isp_stats_event { - uint32_t stats_mask; /* 4 bytes */ - uint8_t stats_buf_idxs[MSM_ISP_STATS_MAX]; /* 11 bytes */ -}; - -struct msm_isp_stream_ack { - uint32_t session_id; - uint32_t stream_id; - uint32_t handle; -}; - -enum msm_vfe_error_type { - ISP_ERROR_NONE, - ISP_ERROR_CAMIF, - ISP_ERROR_BUS_OVERFLOW, - ISP_ERROR_RETURN_EMPTY_BUFFER, - ISP_ERROR_FRAME_ID_MISMATCH, - ISP_ERROR_MAX, -}; - -struct msm_isp_error_info { - enum msm_vfe_error_type err_type; - uint32_t session_id; - uint32_t stream_id; - uint32_t stream_id_mask; -}; - -/* This structure reports delta between master and slave */ -struct msm_isp_ms_delta_info { - uint8_t num_delta_info; - uint32_t delta[MS_NUM_SLAVE_MAX]; -}; - -/* This is sent in EPOCH irq */ -struct msm_isp_output_info { - uint8_t regs_not_updated; - /* mask with bufq_handle for regs not updated or return empty */ - uint16_t output_err_mask; - /* mask with stream_idx for get_buf failed */ - uint8_t stream_framedrop_mask; - /* mask with stats stream_idx for get_buf failed */ - uint16_t stats_framedrop_mask; - /* delta between master and slave */ -}; - -/* This structure is piggybacked with SOF event */ -struct msm_isp_sof_info { - uint8_t regs_not_updated; - /* mask with AXI_SRC for regs not updated */ - uint16_t reg_update_fail_mask; - /* mask with bufq_handle for get_buf failed */ - uint32_t stream_get_buf_fail_mask; - /* mask with stats stream_idx for get_buf failed */ - uint16_t stats_get_buf_fail_mask; - /* delta between master and slave */ - struct msm_isp_ms_delta_info ms_delta_info; -}; - -struct msm_isp_event_data { - /*Wall clock except for buffer divert events - *which use monotonic clock - */ - struct timeval timestamp; - /* Monotonic timestamp since bootup */ - struct timeval mono_timestamp; - uint32_t frame_id; - union { - /* Sent for Stats_Done event */ - struct msm_isp_stats_event stats; - /* Sent for Buf_Divert event */ - struct msm_isp_buf_event buf_done; - /* Sent for offline fetch done event */ - struct msm_isp_fetch_eng_event fetch_done; - /* Sent for Error_Event */ - struct msm_isp_error_info error_info; - /* - * This struct needs to be removed once - * userspace switches to sof_info - */ - struct msm_isp_output_info output_info; - /* Sent for SOF event */ - struct msm_isp_sof_info sof_info; - } u; /* union can have max 52 bytes */ -}; - -#ifdef CONFIG_COMPAT -struct msm_isp_event_data32 { - struct compat_timeval timestamp; - struct compat_timeval mono_timestamp; - uint32_t frame_id; - union { - struct msm_isp_stats_event stats; - struct msm_isp_buf_event buf_done; - struct msm_isp_fetch_eng_event fetch_done; - struct msm_isp_error_info error_info; - struct msm_isp_output_info output_info; - struct msm_isp_sof_info sof_info; - } u; -}; -#endif - -#define V4L2_PIX_FMT_QBGGR8 v4l2_fourcc('Q', 'B', 'G', '8') -#define V4L2_PIX_FMT_QGBRG8 v4l2_fourcc('Q', 'G', 'B', '8') -#define V4L2_PIX_FMT_QGRBG8 v4l2_fourcc('Q', 'G', 'R', '8') -#define V4L2_PIX_FMT_QRGGB8 v4l2_fourcc('Q', 'R', 'G', '8') -#define V4L2_PIX_FMT_QBGGR10 v4l2_fourcc('Q', 'B', 'G', '0') -#define V4L2_PIX_FMT_QGBRG10 v4l2_fourcc('Q', 'G', 'B', '0') -#define V4L2_PIX_FMT_QGRBG10 v4l2_fourcc('Q', 'G', 'R', '0') -#define V4L2_PIX_FMT_QRGGB10 v4l2_fourcc('Q', 'R', 'G', '0') -#define V4L2_PIX_FMT_QBGGR12 v4l2_fourcc('Q', 'B', 'G', '2') -#define V4L2_PIX_FMT_QGBRG12 v4l2_fourcc('Q', 'G', 'B', '2') -#define V4L2_PIX_FMT_QGRBG12 v4l2_fourcc('Q', 'G', 'R', '2') -#define V4L2_PIX_FMT_QRGGB12 v4l2_fourcc('Q', 'R', 'G', '2') -#define V4L2_PIX_FMT_QBGGR14 v4l2_fourcc('Q', 'B', 'G', '4') -#define V4L2_PIX_FMT_QGBRG14 v4l2_fourcc('Q', 'G', 'B', '4') -#define V4L2_PIX_FMT_QGRBG14 v4l2_fourcc('Q', 'G', 'R', '4') -#define V4L2_PIX_FMT_QRGGB14 v4l2_fourcc('Q', 'R', 'G', '4') -#define V4L2_PIX_FMT_P16BGGR10 v4l2_fourcc('P', 'B', 'G', '0') -#define V4L2_PIX_FMT_P16GBRG10 v4l2_fourcc('P', 'G', 'B', '0') -#define V4L2_PIX_FMT_P16GRBG10 v4l2_fourcc('P', 'G', 'R', '0') -#define V4L2_PIX_FMT_P16RGGB10 v4l2_fourcc('P', 'R', 'G', '0') -#define V4L2_PIX_FMT_NV14 v4l2_fourcc('N', 'V', '1', '4') -#define V4L2_PIX_FMT_NV41 v4l2_fourcc('N', 'V', '4', '1') -#define V4L2_PIX_FMT_META v4l2_fourcc('Q', 'M', 'E', 'T') -#define V4L2_PIX_FMT_SBGGR14 v4l2_fourcc('B', 'G', '1', '4') /* 14 BGBG.GRGR.*/ -#define V4L2_PIX_FMT_SGBRG14 v4l2_fourcc('G', 'B', '1', '4') /* 14 GBGB.RGRG.*/ -#define V4L2_PIX_FMT_SGRBG14 v4l2_fourcc('B', 'A', '1', '4') /* 14 GRGR.BGBG.*/ -#define V4L2_PIX_FMT_SRGGB14 v4l2_fourcc('R', 'G', '1', '4') /* 14 RGRG.GBGB.*/ - -#define VIDIOC_MSM_VFE_REG_CFG \ - _IOWR('V', BASE_VIDIOC_PRIVATE, struct msm_vfe_cfg_cmd2) - -#define VIDIOC_MSM_ISP_REQUEST_BUF \ - _IOWR('V', BASE_VIDIOC_PRIVATE+1, struct msm_isp_buf_request) - -#define VIDIOC_MSM_ISP_ENQUEUE_BUF \ - _IOWR('V', BASE_VIDIOC_PRIVATE+2, struct msm_isp_qbuf_info) - -#define VIDIOC_MSM_ISP_RELEASE_BUF \ - _IOWR('V', BASE_VIDIOC_PRIVATE+3, struct msm_isp_buf_request) - -#define VIDIOC_MSM_ISP_REQUEST_STREAM \ - _IOWR('V', BASE_VIDIOC_PRIVATE+4, struct msm_vfe_axi_stream_request_cmd) - -#define VIDIOC_MSM_ISP_CFG_STREAM \ - _IOWR('V', BASE_VIDIOC_PRIVATE+5, struct msm_vfe_axi_stream_cfg_cmd) - -#define VIDIOC_MSM_ISP_RELEASE_STREAM \ - _IOWR('V', BASE_VIDIOC_PRIVATE+6, struct msm_vfe_axi_stream_release_cmd) - -#define VIDIOC_MSM_ISP_INPUT_CFG \ - _IOWR('V', BASE_VIDIOC_PRIVATE+7, struct msm_vfe_input_cfg) - -#define VIDIOC_MSM_ISP_SET_SRC_STATE \ - _IOWR('V', BASE_VIDIOC_PRIVATE+8, struct msm_vfe_axi_src_state) - -#define VIDIOC_MSM_ISP_REQUEST_STATS_STREAM \ - _IOWR('V', BASE_VIDIOC_PRIVATE+9, \ - struct msm_vfe_stats_stream_request_cmd) - -#define VIDIOC_MSM_ISP_CFG_STATS_STREAM \ - _IOWR('V', BASE_VIDIOC_PRIVATE+10, struct msm_vfe_stats_stream_cfg_cmd) - -#define VIDIOC_MSM_ISP_RELEASE_STATS_STREAM \ - _IOWR('V', BASE_VIDIOC_PRIVATE+11, \ - struct msm_vfe_stats_stream_release_cmd) - -#define VIDIOC_MSM_ISP_REG_UPDATE_CMD \ - _IOWR('V', BASE_VIDIOC_PRIVATE+12, enum msm_vfe_input_src) - -#define VIDIOC_MSM_ISP_UPDATE_STREAM \ - _IOWR('V', BASE_VIDIOC_PRIVATE+13, struct msm_vfe_axi_stream_update_cmd) - -#define VIDIOC_MSM_VFE_REG_LIST_CFG \ - _IOWR('V', BASE_VIDIOC_PRIVATE+14, struct msm_vfe_cfg_cmd_list) - -#define VIDIOC_MSM_ISP_SMMU_ATTACH \ - _IOWR('V', BASE_VIDIOC_PRIVATE+15, struct msm_vfe_smmu_attach_cmd) - -#define VIDIOC_MSM_ISP_UPDATE_STATS_STREAM \ - _IOWR('V', BASE_VIDIOC_PRIVATE+16, struct msm_vfe_axi_stream_update_cmd) - -#define VIDIOC_MSM_ISP_AXI_HALT \ - _IOWR('V', BASE_VIDIOC_PRIVATE+17, struct msm_vfe_axi_halt_cmd) - -#define VIDIOC_MSM_ISP_AXI_RESET \ - _IOWR('V', BASE_VIDIOC_PRIVATE+18, struct msm_vfe_axi_reset_cmd) - -#define VIDIOC_MSM_ISP_AXI_RESTART \ - _IOWR('V', BASE_VIDIOC_PRIVATE+19, struct msm_vfe_axi_restart_cmd) - -#define VIDIOC_MSM_ISP_FETCH_ENG_START \ - _IOWR('V', BASE_VIDIOC_PRIVATE+20, struct msm_vfe_fetch_eng_start) - -#define VIDIOC_MSM_ISP_DEQUEUE_BUF \ - _IOWR('V', BASE_VIDIOC_PRIVATE+21, struct msm_isp_qbuf_info) - -#define VIDIOC_MSM_ISP_SET_DUAL_HW_MASTER_SLAVE \ - _IOWR('V', BASE_VIDIOC_PRIVATE+22, struct msm_isp_set_dual_hw_ms_cmd) - -#define VIDIOC_MSM_ISP_MAP_BUF_START_FE \ - _IOWR('V', BASE_VIDIOC_PRIVATE+23, struct msm_vfe_fetch_eng_start) - -#define VIDIOC_MSM_ISP_UNMAP_BUF \ - _IOWR('V', BASE_VIDIOC_PRIVATE+24, struct msm_isp_unmap_buf_req) - -#endif /* __MSMB_ISP__ */ diff --git a/third_party/linux/include/msmb_ispif.h b/third_party/linux/include/msmb_ispif.h deleted file mode 100644 index 2564c33b7b..0000000000 --- a/third_party/linux/include/msmb_ispif.h +++ /dev/null @@ -1,125 +0,0 @@ -#ifndef MSM_CAM_ISPIF_H -#define MSM_CAM_ISPIF_H - -#define CSID_VERSION_V20 0x02000011 -#define CSID_VERSION_V22 0x02001000 -#define CSID_VERSION_V30 0x30000000 -#define CSID_VERSION_V3 0x30000000 - -enum msm_ispif_vfe_intf { - VFE0, - VFE1, - VFE_MAX -}; -#define VFE0_MASK (1 << VFE0) -#define VFE1_MASK (1 << VFE1) - -enum msm_ispif_intftype { - PIX0, - RDI0, - PIX1, - RDI1, - RDI2, - INTF_MAX -}; -#define MAX_PARAM_ENTRIES (INTF_MAX * 2) -#define MAX_CID_CH 8 - -#define PIX0_MASK (1 << PIX0) -#define PIX1_MASK (1 << PIX1) -#define RDI0_MASK (1 << RDI0) -#define RDI1_MASK (1 << RDI1) -#define RDI2_MASK (1 << RDI2) - - -enum msm_ispif_vc { - VC0, - VC1, - VC2, - VC3, - VC_MAX -}; - -enum msm_ispif_cid { - CID0, - CID1, - CID2, - CID3, - CID4, - CID5, - CID6, - CID7, - CID8, - CID9, - CID10, - CID11, - CID12, - CID13, - CID14, - CID15, - CID_MAX -}; - -enum msm_ispif_csid { - CSID0, - CSID1, - CSID2, - CSID3, - CSID_MAX -}; - -struct msm_ispif_params_entry { - enum msm_ispif_vfe_intf vfe_intf; - enum msm_ispif_intftype intftype; - int num_cids; - enum msm_ispif_cid cids[3]; - enum msm_ispif_csid csid; - int crop_enable; - uint16_t crop_start_pixel; - uint16_t crop_end_pixel; -}; - -struct msm_ispif_param_data { - uint32_t num; - struct msm_ispif_params_entry entries[MAX_PARAM_ENTRIES]; -}; - -struct msm_isp_info { - uint32_t max_resolution; - uint32_t id; - uint32_t ver; -}; - -struct msm_ispif_vfe_info { - int num_vfe; - struct msm_isp_info info[VFE_MAX]; -}; - -enum ispif_cfg_type_t { - ISPIF_CLK_ENABLE, - ISPIF_CLK_DISABLE, - ISPIF_INIT, - ISPIF_CFG, - ISPIF_START_FRAME_BOUNDARY, - ISPIF_RESTART_FRAME_BOUNDARY, - ISPIF_STOP_FRAME_BOUNDARY, - ISPIF_STOP_IMMEDIATELY, - ISPIF_RELEASE, - ISPIF_ENABLE_REG_DUMP, - ISPIF_SET_VFE_INFO, -}; - -struct ispif_cfg_data { - enum ispif_cfg_type_t cfg_type; - union { - int reg_dump; /* ISPIF_ENABLE_REG_DUMP */ - uint32_t csid_version; /* ISPIF_INIT */ - struct msm_ispif_vfe_info vfe_info; /* ISPIF_SET_VFE_INFO */ - struct msm_ispif_param_data params; /* CFG, START, STOP */ - }; -}; - -#define VIDIOC_MSM_ISPIF_CFG \ - _IOWR('V', BASE_VIDIOC_PRIVATE, struct ispif_cfg_data) - -#endif /* MSM_CAM_ISPIF_H */ diff --git a/third_party/linux/include/v4l2-controls.h b/third_party/linux/include/v4l2-controls.h deleted file mode 100644 index d14cd8fabe..0000000000 --- a/third_party/linux/include/v4l2-controls.h +++ /dev/null @@ -1,1696 +0,0 @@ -/* - * Video for Linux Two controls header file - * - * Copyright (C) 1999-2012 the contributors - * - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * Alternatively you can redistribute this file under the terms of the - * BSD license as stated below: - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. The names of its contributors may not be used to endorse or promote - * products derived from this software without specific prior written - * permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR - * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT - * OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, - * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED - * TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR - * PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF - * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING - * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS - * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - * The contents of this header was split off from videodev2.h. All control - * definitions should be added to this header, which is included by - * videodev2.h. - */ - -#ifndef __LINUX_V4L2_CONTROLS_H -#define __LINUX_V4L2_CONTROLS_H - -/* Control classes */ -#define V4L2_CTRL_CLASS_USER 0x00980000 /* Old-style 'user' controls */ -#define V4L2_CTRL_CLASS_MPEG 0x00990000 /* MPEG-compression controls */ -#define V4L2_CTRL_CLASS_CAMERA 0x009a0000 /* Camera class controls */ -#define V4L2_CTRL_CLASS_FM_TX 0x009b0000 /* FM Modulator controls */ -#define V4L2_CTRL_CLASS_FLASH 0x009c0000 /* Camera flash controls */ -#define V4L2_CTRL_CLASS_JPEG 0x009d0000 /* JPEG-compression controls */ -#define V4L2_CTRL_CLASS_IMAGE_SOURCE 0x009e0000 /* Image source controls */ -#define V4L2_CTRL_CLASS_IMAGE_PROC 0x009f0000 /* Image processing controls */ -#define V4L2_CTRL_CLASS_DV 0x00a00000 /* Digital Video controls */ -#define V4L2_CTRL_CLASS_FM_RX 0x00a10000 /* FM Receiver controls */ -#define V4L2_CTRL_CLASS_RF_TUNER 0x00a20000 /* RF tuner controls */ -#define V4L2_CTRL_CLASS_DETECT 0x00a30000 /* Detection controls */ - -/* User-class control IDs */ - -#define V4L2_CID_BASE (V4L2_CTRL_CLASS_USER | 0x900) -#define V4L2_CID_USER_BASE V4L2_CID_BASE -#define V4L2_CID_USER_CLASS (V4L2_CTRL_CLASS_USER | 1) -#define V4L2_CID_BRIGHTNESS (V4L2_CID_BASE+0) -#define V4L2_CID_CONTRAST (V4L2_CID_BASE+1) -#define V4L2_CID_SATURATION (V4L2_CID_BASE+2) -#define V4L2_CID_HUE (V4L2_CID_BASE+3) -#define V4L2_CID_AUDIO_VOLUME (V4L2_CID_BASE+5) -#define V4L2_CID_AUDIO_BALANCE (V4L2_CID_BASE+6) -#define V4L2_CID_AUDIO_BASS (V4L2_CID_BASE+7) -#define V4L2_CID_AUDIO_TREBLE (V4L2_CID_BASE+8) -#define V4L2_CID_AUDIO_MUTE (V4L2_CID_BASE+9) -#define V4L2_CID_AUDIO_LOUDNESS (V4L2_CID_BASE+10) -#define V4L2_CID_BLACK_LEVEL (V4L2_CID_BASE+11) /* Deprecated */ -#define V4L2_CID_AUTO_WHITE_BALANCE (V4L2_CID_BASE+12) -#define V4L2_CID_DO_WHITE_BALANCE (V4L2_CID_BASE+13) -#define V4L2_CID_RED_BALANCE (V4L2_CID_BASE+14) -#define V4L2_CID_BLUE_BALANCE (V4L2_CID_BASE+15) -#define V4L2_CID_GAMMA (V4L2_CID_BASE+16) -#define V4L2_CID_WHITENESS (V4L2_CID_GAMMA) /* Deprecated */ -#define V4L2_CID_EXPOSURE (V4L2_CID_BASE+17) -#define V4L2_CID_AUTOGAIN (V4L2_CID_BASE+18) -#define V4L2_CID_GAIN (V4L2_CID_BASE+19) -#define V4L2_CID_HFLIP (V4L2_CID_BASE+20) -#define V4L2_CID_VFLIP (V4L2_CID_BASE+21) - -#define V4L2_CID_POWER_LINE_FREQUENCY (V4L2_CID_BASE+24) -enum v4l2_power_line_frequency { - V4L2_CID_POWER_LINE_FREQUENCY_DISABLED = 0, - V4L2_CID_POWER_LINE_FREQUENCY_50HZ = 1, - V4L2_CID_POWER_LINE_FREQUENCY_60HZ = 2, - V4L2_CID_POWER_LINE_FREQUENCY_AUTO = 3, -}; -#define V4L2_CID_HUE_AUTO (V4L2_CID_BASE+25) -#define V4L2_CID_WHITE_BALANCE_TEMPERATURE (V4L2_CID_BASE+26) -#define V4L2_CID_SHARPNESS (V4L2_CID_BASE+27) -#define V4L2_CID_BACKLIGHT_COMPENSATION (V4L2_CID_BASE+28) -#define V4L2_CID_CHROMA_AGC (V4L2_CID_BASE+29) -#define V4L2_CID_COLOR_KILLER (V4L2_CID_BASE+30) -#define V4L2_CID_COLORFX (V4L2_CID_BASE+31) -enum v4l2_colorfx { - V4L2_COLORFX_NONE = 0, - V4L2_COLORFX_BW = 1, - V4L2_COLORFX_SEPIA = 2, - V4L2_COLORFX_NEGATIVE = 3, - V4L2_COLORFX_EMBOSS = 4, - V4L2_COLORFX_SKETCH = 5, - V4L2_COLORFX_SKY_BLUE = 6, - V4L2_COLORFX_GRASS_GREEN = 7, - V4L2_COLORFX_SKIN_WHITEN = 8, - V4L2_COLORFX_VIVID = 9, - V4L2_COLORFX_AQUA = 10, - V4L2_COLORFX_ART_FREEZE = 11, - V4L2_COLORFX_SILHOUETTE = 12, - V4L2_COLORFX_SOLARIZATION = 13, - V4L2_COLORFX_ANTIQUE = 14, - V4L2_COLORFX_SET_CBCR = 15, -}; -#define V4L2_CID_AUTOBRIGHTNESS (V4L2_CID_BASE+32) -#define V4L2_CID_BAND_STOP_FILTER (V4L2_CID_BASE+33) - -#define V4L2_CID_ROTATE (V4L2_CID_BASE+34) -#define V4L2_CID_BG_COLOR (V4L2_CID_BASE+35) - -#define V4L2_CID_CHROMA_GAIN (V4L2_CID_BASE+36) - -#define V4L2_CID_ILLUMINATORS_1 (V4L2_CID_BASE+37) -#define V4L2_CID_ILLUMINATORS_2 (V4L2_CID_BASE+38) - -#define V4L2_CID_MIN_BUFFERS_FOR_CAPTURE (V4L2_CID_BASE+39) -#define V4L2_CID_MIN_BUFFERS_FOR_OUTPUT (V4L2_CID_BASE+40) - -#define V4L2_CID_ALPHA_COMPONENT (V4L2_CID_BASE+41) -#define V4L2_CID_COLORFX_CBCR (V4L2_CID_BASE+42) - -/* last CID + 1 */ -#define V4L2_CID_LASTP1 (V4L2_CID_BASE+43) - -/* USER-class private control IDs */ - -/* The base for the meye driver controls. See linux/meye.h for the list - * of controls. We reserve 16 controls for this driver. */ -#define V4L2_CID_USER_MEYE_BASE (V4L2_CID_USER_BASE + 0x1000) - -/* The base for the bttv driver controls. - * We reserve 32 controls for this driver. */ -#define V4L2_CID_USER_BTTV_BASE (V4L2_CID_USER_BASE + 0x1010) - - -/* The base for the s2255 driver controls. - * We reserve 16 controls for this driver. */ -#define V4L2_CID_USER_S2255_BASE (V4L2_CID_USER_BASE + 0x1030) - -/* - * The base for the si476x driver controls. See include/media/drv-intf/si476x.h - * for the list of controls. Total of 16 controls is reserved for this driver - */ -#define V4L2_CID_USER_SI476X_BASE (V4L2_CID_USER_BASE + 0x1040) - -/* The base for the TI VPE driver controls. Total of 16 controls is reserved for - * this driver */ -#define V4L2_CID_USER_TI_VPE_BASE (V4L2_CID_USER_BASE + 0x1050) - -/* The base for the saa7134 driver controls. - * We reserve 16 controls for this driver. */ -#define V4L2_CID_USER_SAA7134_BASE (V4L2_CID_USER_BASE + 0x1060) - -/* The base for the adv7180 driver controls. - * We reserve 16 controls for this driver. */ -#define V4L2_CID_USER_ADV7180_BASE (V4L2_CID_USER_BASE + 0x1070) - -/* The base for the tc358743 driver controls. - * We reserve 16 controls for this driver. */ -#define V4L2_CID_USER_TC358743_BASE (V4L2_CID_USER_BASE + 0x1080) - -/* MPEG-class control IDs */ -/* The MPEG controls are applicable to all codec controls - * and the 'MPEG' part of the define is historical */ - -#define V4L2_CID_MPEG_BASE (V4L2_CTRL_CLASS_MPEG | 0x900) -#define V4L2_CID_MPEG_CLASS (V4L2_CTRL_CLASS_MPEG | 1) - -/* MPEG streams, specific to multiplexed streams */ -#define V4L2_CID_MPEG_STREAM_TYPE (V4L2_CID_MPEG_BASE+0) -enum v4l2_mpeg_stream_type { - V4L2_MPEG_STREAM_TYPE_MPEG2_PS = 0, /* MPEG-2 program stream */ - V4L2_MPEG_STREAM_TYPE_MPEG2_TS = 1, /* MPEG-2 transport stream */ - V4L2_MPEG_STREAM_TYPE_MPEG1_SS = 2, /* MPEG-1 system stream */ - V4L2_MPEG_STREAM_TYPE_MPEG2_DVD = 3, /* MPEG-2 DVD-compatible stream */ - V4L2_MPEG_STREAM_TYPE_MPEG1_VCD = 4, /* MPEG-1 VCD-compatible stream */ - V4L2_MPEG_STREAM_TYPE_MPEG2_SVCD = 5, /* MPEG-2 SVCD-compatible stream */ -}; -#define V4L2_CID_MPEG_STREAM_PID_PMT (V4L2_CID_MPEG_BASE+1) -#define V4L2_CID_MPEG_STREAM_PID_AUDIO (V4L2_CID_MPEG_BASE+2) -#define V4L2_CID_MPEG_STREAM_PID_VIDEO (V4L2_CID_MPEG_BASE+3) -#define V4L2_CID_MPEG_STREAM_PID_PCR (V4L2_CID_MPEG_BASE+4) -#define V4L2_CID_MPEG_STREAM_PES_ID_AUDIO (V4L2_CID_MPEG_BASE+5) -#define V4L2_CID_MPEG_STREAM_PES_ID_VIDEO (V4L2_CID_MPEG_BASE+6) -#define V4L2_CID_MPEG_STREAM_VBI_FMT (V4L2_CID_MPEG_BASE+7) -enum v4l2_mpeg_stream_vbi_fmt { - V4L2_MPEG_STREAM_VBI_FMT_NONE = 0, /* No VBI in the MPEG stream */ - V4L2_MPEG_STREAM_VBI_FMT_IVTV = 1, /* VBI in private packets, IVTV format */ -}; - -/* MPEG audio controls specific to multiplexed streams */ -#define V4L2_CID_MPEG_AUDIO_SAMPLING_FREQ (V4L2_CID_MPEG_BASE+100) -enum v4l2_mpeg_audio_sampling_freq { - V4L2_MPEG_AUDIO_SAMPLING_FREQ_44100 = 0, - V4L2_MPEG_AUDIO_SAMPLING_FREQ_48000 = 1, - V4L2_MPEG_AUDIO_SAMPLING_FREQ_32000 = 2, -}; -#define V4L2_CID_MPEG_AUDIO_ENCODING (V4L2_CID_MPEG_BASE+101) -enum v4l2_mpeg_audio_encoding { - V4L2_MPEG_AUDIO_ENCODING_LAYER_1 = 0, - V4L2_MPEG_AUDIO_ENCODING_LAYER_2 = 1, - V4L2_MPEG_AUDIO_ENCODING_LAYER_3 = 2, - V4L2_MPEG_AUDIO_ENCODING_AAC = 3, - V4L2_MPEG_AUDIO_ENCODING_AC3 = 4, -}; -#define V4L2_CID_MPEG_AUDIO_L1_BITRATE (V4L2_CID_MPEG_BASE+102) -enum v4l2_mpeg_audio_l1_bitrate { - V4L2_MPEG_AUDIO_L1_BITRATE_32K = 0, - V4L2_MPEG_AUDIO_L1_BITRATE_64K = 1, - V4L2_MPEG_AUDIO_L1_BITRATE_96K = 2, - V4L2_MPEG_AUDIO_L1_BITRATE_128K = 3, - V4L2_MPEG_AUDIO_L1_BITRATE_160K = 4, - V4L2_MPEG_AUDIO_L1_BITRATE_192K = 5, - V4L2_MPEG_AUDIO_L1_BITRATE_224K = 6, - V4L2_MPEG_AUDIO_L1_BITRATE_256K = 7, - V4L2_MPEG_AUDIO_L1_BITRATE_288K = 8, - V4L2_MPEG_AUDIO_L1_BITRATE_320K = 9, - V4L2_MPEG_AUDIO_L1_BITRATE_352K = 10, - V4L2_MPEG_AUDIO_L1_BITRATE_384K = 11, - V4L2_MPEG_AUDIO_L1_BITRATE_416K = 12, - V4L2_MPEG_AUDIO_L1_BITRATE_448K = 13, -}; -#define V4L2_CID_MPEG_AUDIO_L2_BITRATE (V4L2_CID_MPEG_BASE+103) -enum v4l2_mpeg_audio_l2_bitrate { - V4L2_MPEG_AUDIO_L2_BITRATE_32K = 0, - V4L2_MPEG_AUDIO_L2_BITRATE_48K = 1, - V4L2_MPEG_AUDIO_L2_BITRATE_56K = 2, - V4L2_MPEG_AUDIO_L2_BITRATE_64K = 3, - V4L2_MPEG_AUDIO_L2_BITRATE_80K = 4, - V4L2_MPEG_AUDIO_L2_BITRATE_96K = 5, - V4L2_MPEG_AUDIO_L2_BITRATE_112K = 6, - V4L2_MPEG_AUDIO_L2_BITRATE_128K = 7, - V4L2_MPEG_AUDIO_L2_BITRATE_160K = 8, - V4L2_MPEG_AUDIO_L2_BITRATE_192K = 9, - V4L2_MPEG_AUDIO_L2_BITRATE_224K = 10, - V4L2_MPEG_AUDIO_L2_BITRATE_256K = 11, - V4L2_MPEG_AUDIO_L2_BITRATE_320K = 12, - V4L2_MPEG_AUDIO_L2_BITRATE_384K = 13, -}; -#define V4L2_CID_MPEG_AUDIO_L3_BITRATE (V4L2_CID_MPEG_BASE+104) -enum v4l2_mpeg_audio_l3_bitrate { - V4L2_MPEG_AUDIO_L3_BITRATE_32K = 0, - V4L2_MPEG_AUDIO_L3_BITRATE_40K = 1, - V4L2_MPEG_AUDIO_L3_BITRATE_48K = 2, - V4L2_MPEG_AUDIO_L3_BITRATE_56K = 3, - V4L2_MPEG_AUDIO_L3_BITRATE_64K = 4, - V4L2_MPEG_AUDIO_L3_BITRATE_80K = 5, - V4L2_MPEG_AUDIO_L3_BITRATE_96K = 6, - V4L2_MPEG_AUDIO_L3_BITRATE_112K = 7, - V4L2_MPEG_AUDIO_L3_BITRATE_128K = 8, - V4L2_MPEG_AUDIO_L3_BITRATE_160K = 9, - V4L2_MPEG_AUDIO_L3_BITRATE_192K = 10, - V4L2_MPEG_AUDIO_L3_BITRATE_224K = 11, - V4L2_MPEG_AUDIO_L3_BITRATE_256K = 12, - V4L2_MPEG_AUDIO_L3_BITRATE_320K = 13, -}; -#define V4L2_CID_MPEG_AUDIO_MODE (V4L2_CID_MPEG_BASE+105) -enum v4l2_mpeg_audio_mode { - V4L2_MPEG_AUDIO_MODE_STEREO = 0, - V4L2_MPEG_AUDIO_MODE_JOINT_STEREO = 1, - V4L2_MPEG_AUDIO_MODE_DUAL = 2, - V4L2_MPEG_AUDIO_MODE_MONO = 3, -}; -#define V4L2_CID_MPEG_AUDIO_MODE_EXTENSION (V4L2_CID_MPEG_BASE+106) -enum v4l2_mpeg_audio_mode_extension { - V4L2_MPEG_AUDIO_MODE_EXTENSION_BOUND_4 = 0, - V4L2_MPEG_AUDIO_MODE_EXTENSION_BOUND_8 = 1, - V4L2_MPEG_AUDIO_MODE_EXTENSION_BOUND_12 = 2, - V4L2_MPEG_AUDIO_MODE_EXTENSION_BOUND_16 = 3, -}; -#define V4L2_CID_MPEG_AUDIO_EMPHASIS (V4L2_CID_MPEG_BASE+107) -enum v4l2_mpeg_audio_emphasis { - V4L2_MPEG_AUDIO_EMPHASIS_NONE = 0, - V4L2_MPEG_AUDIO_EMPHASIS_50_DIV_15_uS = 1, - V4L2_MPEG_AUDIO_EMPHASIS_CCITT_J17 = 2, -}; -#define V4L2_CID_MPEG_AUDIO_CRC (V4L2_CID_MPEG_BASE+108) -enum v4l2_mpeg_audio_crc { - V4L2_MPEG_AUDIO_CRC_NONE = 0, - V4L2_MPEG_AUDIO_CRC_CRC16 = 1, -}; -#define V4L2_CID_MPEG_AUDIO_MUTE (V4L2_CID_MPEG_BASE+109) -#define V4L2_CID_MPEG_AUDIO_AAC_BITRATE (V4L2_CID_MPEG_BASE+110) -#define V4L2_CID_MPEG_AUDIO_AC3_BITRATE (V4L2_CID_MPEG_BASE+111) -enum v4l2_mpeg_audio_ac3_bitrate { - V4L2_MPEG_AUDIO_AC3_BITRATE_32K = 0, - V4L2_MPEG_AUDIO_AC3_BITRATE_40K = 1, - V4L2_MPEG_AUDIO_AC3_BITRATE_48K = 2, - V4L2_MPEG_AUDIO_AC3_BITRATE_56K = 3, - V4L2_MPEG_AUDIO_AC3_BITRATE_64K = 4, - V4L2_MPEG_AUDIO_AC3_BITRATE_80K = 5, - V4L2_MPEG_AUDIO_AC3_BITRATE_96K = 6, - V4L2_MPEG_AUDIO_AC3_BITRATE_112K = 7, - V4L2_MPEG_AUDIO_AC3_BITRATE_128K = 8, - V4L2_MPEG_AUDIO_AC3_BITRATE_160K = 9, - V4L2_MPEG_AUDIO_AC3_BITRATE_192K = 10, - V4L2_MPEG_AUDIO_AC3_BITRATE_224K = 11, - V4L2_MPEG_AUDIO_AC3_BITRATE_256K = 12, - V4L2_MPEG_AUDIO_AC3_BITRATE_320K = 13, - V4L2_MPEG_AUDIO_AC3_BITRATE_384K = 14, - V4L2_MPEG_AUDIO_AC3_BITRATE_448K = 15, - V4L2_MPEG_AUDIO_AC3_BITRATE_512K = 16, - V4L2_MPEG_AUDIO_AC3_BITRATE_576K = 17, - V4L2_MPEG_AUDIO_AC3_BITRATE_640K = 18, -}; -#define V4L2_CID_MPEG_AUDIO_DEC_PLAYBACK (V4L2_CID_MPEG_BASE+112) -enum v4l2_mpeg_audio_dec_playback { - V4L2_MPEG_AUDIO_DEC_PLAYBACK_AUTO = 0, - V4L2_MPEG_AUDIO_DEC_PLAYBACK_STEREO = 1, - V4L2_MPEG_AUDIO_DEC_PLAYBACK_LEFT = 2, - V4L2_MPEG_AUDIO_DEC_PLAYBACK_RIGHT = 3, - V4L2_MPEG_AUDIO_DEC_PLAYBACK_MONO = 4, - V4L2_MPEG_AUDIO_DEC_PLAYBACK_SWAPPED_STEREO = 5, -}; -#define V4L2_CID_MPEG_AUDIO_DEC_MULTILINGUAL_PLAYBACK (V4L2_CID_MPEG_BASE+113) - -/* MPEG video controls specific to multiplexed streams */ -#define V4L2_CID_MPEG_VIDEO_ENCODING (V4L2_CID_MPEG_BASE+200) -enum v4l2_mpeg_video_encoding { - V4L2_MPEG_VIDEO_ENCODING_MPEG_1 = 0, - V4L2_MPEG_VIDEO_ENCODING_MPEG_2 = 1, - V4L2_MPEG_VIDEO_ENCODING_MPEG_4_AVC = 2, -}; -#define V4L2_CID_MPEG_VIDEO_ASPECT (V4L2_CID_MPEG_BASE+201) -enum v4l2_mpeg_video_aspect { - V4L2_MPEG_VIDEO_ASPECT_1x1 = 0, - V4L2_MPEG_VIDEO_ASPECT_4x3 = 1, - V4L2_MPEG_VIDEO_ASPECT_16x9 = 2, - V4L2_MPEG_VIDEO_ASPECT_221x100 = 3, -}; -#define V4L2_CID_MPEG_VIDEO_B_FRAMES (V4L2_CID_MPEG_BASE+202) -#define V4L2_CID_MPEG_VIDEO_GOP_SIZE (V4L2_CID_MPEG_BASE+203) -#define V4L2_CID_MPEG_VIDEO_GOP_CLOSURE (V4L2_CID_MPEG_BASE+204) -#define V4L2_CID_MPEG_VIDEO_PULLDOWN (V4L2_CID_MPEG_BASE+205) -#define V4L2_CID_MPEG_VIDEO_BITRATE_MODE (V4L2_CID_MPEG_BASE+206) -enum v4l2_mpeg_video_bitrate_mode { - V4L2_MPEG_VIDEO_BITRATE_MODE_VBR = 0, - V4L2_MPEG_VIDEO_BITRATE_MODE_CBR = 1, -}; -#define V4L2_CID_MPEG_VIDEO_BITRATE (V4L2_CID_MPEG_BASE+207) -#define V4L2_CID_MPEG_VIDEO_BITRATE_PEAK (V4L2_CID_MPEG_BASE+208) -#define V4L2_CID_MPEG_VIDEO_TEMPORAL_DECIMATION (V4L2_CID_MPEG_BASE+209) -#define V4L2_CID_MPEG_VIDEO_MUTE (V4L2_CID_MPEG_BASE+210) -#define V4L2_CID_MPEG_VIDEO_MUTE_YUV (V4L2_CID_MPEG_BASE+211) -#define V4L2_CID_MPEG_VIDEO_DECODER_SLICE_INTERFACE (V4L2_CID_MPEG_BASE+212) -#define V4L2_CID_MPEG_VIDEO_DECODER_MPEG4_DEBLOCK_FILTER (V4L2_CID_MPEG_BASE+213) -#define V4L2_CID_MPEG_VIDEO_CYCLIC_INTRA_REFRESH_MB (V4L2_CID_MPEG_BASE+214) -#define V4L2_CID_MPEG_VIDEO_FRAME_RC_ENABLE (V4L2_CID_MPEG_BASE+215) -#define V4L2_CID_MPEG_VIDEO_HEADER_MODE (V4L2_CID_MPEG_BASE+216) -enum v4l2_mpeg_video_header_mode { - V4L2_MPEG_VIDEO_HEADER_MODE_SEPARATE = 0, - V4L2_MPEG_VIDEO_HEADER_MODE_JOINED_WITH_1ST_FRAME = 1, - V4L2_MPEG_VIDEO_HEADER_MODE_JOINED_WITH_I_FRAME = 2, -}; -#define V4L2_CID_MPEG_VIDEO_MAX_REF_PIC (V4L2_CID_MPEG_BASE+217) -#define V4L2_CID_MPEG_VIDEO_MB_RC_ENABLE (V4L2_CID_MPEG_BASE+218) -#define V4L2_CID_MPEG_VIDEO_MULTI_SLICE_MAX_BYTES (V4L2_CID_MPEG_BASE+219) -#define V4L2_CID_MPEG_VIDEO_MULTI_SLICE_MAX_MB (V4L2_CID_MPEG_BASE+220) -#define V4L2_CID_MPEG_VIDEO_MULTI_SLICE_MODE (V4L2_CID_MPEG_BASE+221) -enum v4l2_mpeg_video_multi_slice_mode { - V4L2_MPEG_VIDEO_MULTI_SLICE_MODE_SINGLE = 0, - V4L2_MPEG_VIDEO_MULTI_SICE_MODE_MAX_MB = 1, - V4L2_MPEG_VIDEO_MULTI_SICE_MODE_MAX_BYTES = 2, - V4L2_MPEG_VIDEO_MULTI_SLICE_GOB = 3, -}; -#define V4L2_CID_MPEG_VIDEO_VBV_SIZE (V4L2_CID_MPEG_BASE+222) -#define V4L2_CID_MPEG_VIDEO_DEC_PTS (V4L2_CID_MPEG_BASE+223) -#define V4L2_CID_MPEG_VIDEO_DEC_FRAME (V4L2_CID_MPEG_BASE+224) -#define V4L2_CID_MPEG_VIDEO_VBV_DELAY (V4L2_CID_MPEG_BASE+225) -#define V4L2_CID_MPEG_VIDEO_REPEAT_SEQ_HEADER (V4L2_CID_MPEG_BASE+226) -#define V4L2_CID_MPEG_VIDEO_MV_H_SEARCH_RANGE (V4L2_CID_MPEG_BASE+227) -#define V4L2_CID_MPEG_VIDEO_MV_V_SEARCH_RANGE (V4L2_CID_MPEG_BASE+228) -#define V4L2_CID_MPEG_VIDEO_FORCE_KEY_FRAME (V4L2_CID_MPEG_BASE+229) - -#define V4L2_CID_MPEG_VIDEO_H263_I_FRAME_QP (V4L2_CID_MPEG_BASE+300) -#define V4L2_CID_MPEG_VIDEO_H263_P_FRAME_QP (V4L2_CID_MPEG_BASE+301) -#define V4L2_CID_MPEG_VIDEO_H263_B_FRAME_QP (V4L2_CID_MPEG_BASE+302) -#define V4L2_CID_MPEG_VIDEO_H263_MIN_QP (V4L2_CID_MPEG_BASE+303) -#define V4L2_CID_MPEG_VIDEO_H263_MAX_QP (V4L2_CID_MPEG_BASE+304) -#define V4L2_CID_MPEG_VIDEO_H264_I_FRAME_QP (V4L2_CID_MPEG_BASE+350) -#define V4L2_CID_MPEG_VIDEO_H264_P_FRAME_QP (V4L2_CID_MPEG_BASE+351) -#define V4L2_CID_MPEG_VIDEO_H264_B_FRAME_QP (V4L2_CID_MPEG_BASE+352) -#define V4L2_CID_MPEG_VIDEO_H264_MIN_QP (V4L2_CID_MPEG_BASE+353) -#define V4L2_CID_MPEG_VIDEO_H264_MAX_QP (V4L2_CID_MPEG_BASE+354) -#define V4L2_CID_MPEG_VIDEO_H264_8X8_TRANSFORM (V4L2_CID_MPEG_BASE+355) -#define V4L2_CID_MPEG_VIDEO_H264_CPB_SIZE (V4L2_CID_MPEG_BASE+356) -#define V4L2_CID_MPEG_VIDEO_H264_ENTROPY_MODE (V4L2_CID_MPEG_BASE+357) -enum v4l2_mpeg_video_h264_entropy_mode { - V4L2_MPEG_VIDEO_H264_ENTROPY_MODE_CAVLC = 0, - V4L2_MPEG_VIDEO_H264_ENTROPY_MODE_CABAC = 1, -}; -#define V4L2_CID_MPEG_VIDEO_H264_I_PERIOD (V4L2_CID_MPEG_BASE+358) -#define V4L2_CID_MPEG_VIDEO_H264_LEVEL (V4L2_CID_MPEG_BASE+359) -enum v4l2_mpeg_video_h264_level { - V4L2_MPEG_VIDEO_H264_LEVEL_1_0 = 0, - V4L2_MPEG_VIDEO_H264_LEVEL_1B = 1, - V4L2_MPEG_VIDEO_H264_LEVEL_1_1 = 2, - V4L2_MPEG_VIDEO_H264_LEVEL_1_2 = 3, - V4L2_MPEG_VIDEO_H264_LEVEL_1_3 = 4, - V4L2_MPEG_VIDEO_H264_LEVEL_2_0 = 5, - V4L2_MPEG_VIDEO_H264_LEVEL_2_1 = 6, - V4L2_MPEG_VIDEO_H264_LEVEL_2_2 = 7, - V4L2_MPEG_VIDEO_H264_LEVEL_3_0 = 8, - V4L2_MPEG_VIDEO_H264_LEVEL_3_1 = 9, - V4L2_MPEG_VIDEO_H264_LEVEL_3_2 = 10, - V4L2_MPEG_VIDEO_H264_LEVEL_4_0 = 11, - V4L2_MPEG_VIDEO_H264_LEVEL_4_1 = 12, - V4L2_MPEG_VIDEO_H264_LEVEL_4_2 = 13, - V4L2_MPEG_VIDEO_H264_LEVEL_5_0 = 14, - V4L2_MPEG_VIDEO_H264_LEVEL_5_1 = 15, - V4L2_MPEG_VIDEO_H264_LEVEL_5_2 = 16, -#define V4L2_MPEG_VIDEO_H264_LEVEL_UNKNOWN \ - V4L2_MPEG_VIDEO_H264_LEVEL_UNKNOWN - V4L2_MPEG_VIDEO_H264_LEVEL_UNKNOWN = 17, -}; -#define V4L2_CID_MPEG_VIDEO_H264_LOOP_FILTER_ALPHA (V4L2_CID_MPEG_BASE+360) -#define V4L2_CID_MPEG_VIDEO_H264_LOOP_FILTER_BETA (V4L2_CID_MPEG_BASE+361) -#define V4L2_CID_MPEG_VIDEO_H264_LOOP_FILTER_MODE (V4L2_CID_MPEG_BASE+362) -enum v4l2_mpeg_video_h264_loop_filter_mode { - V4L2_MPEG_VIDEO_H264_LOOP_FILTER_MODE_ENABLED = 0, - V4L2_MPEG_VIDEO_H264_LOOP_FILTER_MODE_DISABLED = 1, - V4L2_MPEG_VIDEO_H264_LOOP_FILTER_MODE_DISABLED_AT_SLICE_BOUNDARY = 2, -}; -#define V4L2_CID_MPEG_VIDEO_H264_PROFILE (V4L2_CID_MPEG_BASE+363) -enum v4l2_mpeg_video_h264_profile { - V4L2_MPEG_VIDEO_H264_PROFILE_BASELINE = 0, - V4L2_MPEG_VIDEO_H264_PROFILE_CONSTRAINED_BASELINE = 1, - V4L2_MPEG_VIDEO_H264_PROFILE_MAIN = 2, - V4L2_MPEG_VIDEO_H264_PROFILE_EXTENDED = 3, - V4L2_MPEG_VIDEO_H264_PROFILE_HIGH = 4, - V4L2_MPEG_VIDEO_H264_PROFILE_HIGH_10 = 5, - V4L2_MPEG_VIDEO_H264_PROFILE_HIGH_422 = 6, - V4L2_MPEG_VIDEO_H264_PROFILE_HIGH_444_PREDICTIVE = 7, - V4L2_MPEG_VIDEO_H264_PROFILE_HIGH_10_INTRA = 8, - V4L2_MPEG_VIDEO_H264_PROFILE_HIGH_422_INTRA = 9, - V4L2_MPEG_VIDEO_H264_PROFILE_HIGH_444_INTRA = 10, - V4L2_MPEG_VIDEO_H264_PROFILE_CAVLC_444_INTRA = 11, - V4L2_MPEG_VIDEO_H264_PROFILE_SCALABLE_BASELINE = 12, - V4L2_MPEG_VIDEO_H264_PROFILE_SCALABLE_HIGH = 13, - V4L2_MPEG_VIDEO_H264_PROFILE_SCALABLE_HIGH_INTRA = 14, - V4L2_MPEG_VIDEO_H264_PROFILE_STEREO_HIGH = 15, - V4L2_MPEG_VIDEO_H264_PROFILE_MULTIVIEW_HIGH = 16, - V4L2_MPEG_VIDEO_H264_PROFILE_CONSTRAINED_HIGH = 17, -}; -#define V4L2_CID_MPEG_VIDEO_H264_VUI_EXT_SAR_HEIGHT (V4L2_CID_MPEG_BASE+364) -#define V4L2_CID_MPEG_VIDEO_H264_VUI_EXT_SAR_WIDTH (V4L2_CID_MPEG_BASE+365) -#define V4L2_CID_MPEG_VIDEO_H264_VUI_SAR_ENABLE (V4L2_CID_MPEG_BASE+366) -#define V4L2_CID_MPEG_VIDEO_H264_VUI_SAR_IDC (V4L2_CID_MPEG_BASE+367) -enum v4l2_mpeg_video_h264_vui_sar_idc { - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_UNSPECIFIED = 0, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_1x1 = 1, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_12x11 = 2, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_10x11 = 3, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_16x11 = 4, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_40x33 = 5, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_24x11 = 6, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_20x11 = 7, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_32x11 = 8, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_80x33 = 9, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_18x11 = 10, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_15x11 = 11, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_64x33 = 12, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_160x99 = 13, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_4x3 = 14, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_3x2 = 15, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_2x1 = 16, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_EXTENDED = 17, -}; -#define V4L2_CID_MPEG_VIDEO_H264_SEI_FRAME_PACKING (V4L2_CID_MPEG_BASE+368) -#define V4L2_CID_MPEG_VIDEO_H264_SEI_FP_CURRENT_FRAME_0 (V4L2_CID_MPEG_BASE+369) -#define V4L2_CID_MPEG_VIDEO_H264_SEI_FP_ARRANGEMENT_TYPE (V4L2_CID_MPEG_BASE+370) -enum v4l2_mpeg_video_h264_sei_fp_arrangement_type { - V4L2_MPEG_VIDEO_H264_SEI_FP_ARRANGEMENT_TYPE_CHECKERBOARD = 0, - V4L2_MPEG_VIDEO_H264_SEI_FP_ARRANGEMENT_TYPE_COLUMN = 1, - V4L2_MPEG_VIDEO_H264_SEI_FP_ARRANGEMENT_TYPE_ROW = 2, - V4L2_MPEG_VIDEO_H264_SEI_FP_ARRANGEMENT_TYPE_SIDE_BY_SIDE = 3, - V4L2_MPEG_VIDEO_H264_SEI_FP_ARRANGEMENT_TYPE_TOP_BOTTOM = 4, - V4L2_MPEG_VIDEO_H264_SEI_FP_ARRANGEMENT_TYPE_TEMPORAL = 5, -}; -#define V4L2_CID_MPEG_VIDEO_H264_FMO (V4L2_CID_MPEG_BASE+371) -#define V4L2_CID_MPEG_VIDEO_H264_FMO_MAP_TYPE (V4L2_CID_MPEG_BASE+372) -enum v4l2_mpeg_video_h264_fmo_map_type { - V4L2_MPEG_VIDEO_H264_FMO_MAP_TYPE_INTERLEAVED_SLICES = 0, - V4L2_MPEG_VIDEO_H264_FMO_MAP_TYPE_SCATTERED_SLICES = 1, - V4L2_MPEG_VIDEO_H264_FMO_MAP_TYPE_FOREGROUND_WITH_LEFT_OVER = 2, - V4L2_MPEG_VIDEO_H264_FMO_MAP_TYPE_BOX_OUT = 3, - V4L2_MPEG_VIDEO_H264_FMO_MAP_TYPE_RASTER_SCAN = 4, - V4L2_MPEG_VIDEO_H264_FMO_MAP_TYPE_WIPE_SCAN = 5, - V4L2_MPEG_VIDEO_H264_FMO_MAP_TYPE_EXPLICIT = 6, -}; -#define V4L2_CID_MPEG_VIDEO_H264_FMO_SLICE_GROUP (V4L2_CID_MPEG_BASE+373) -#define V4L2_CID_MPEG_VIDEO_H264_FMO_CHANGE_DIRECTION (V4L2_CID_MPEG_BASE+374) -enum v4l2_mpeg_video_h264_fmo_change_dir { - V4L2_MPEG_VIDEO_H264_FMO_CHANGE_DIR_RIGHT = 0, - V4L2_MPEG_VIDEO_H264_FMO_CHANGE_DIR_LEFT = 1, -}; -#define V4L2_CID_MPEG_VIDEO_H264_FMO_CHANGE_RATE (V4L2_CID_MPEG_BASE+375) -#define V4L2_CID_MPEG_VIDEO_H264_FMO_RUN_LENGTH (V4L2_CID_MPEG_BASE+376) -#define V4L2_CID_MPEG_VIDEO_H264_ASO (V4L2_CID_MPEG_BASE+377) -#define V4L2_CID_MPEG_VIDEO_H264_ASO_SLICE_ORDER (V4L2_CID_MPEG_BASE+378) -#define V4L2_CID_MPEG_VIDEO_H264_HIERARCHICAL_CODING (V4L2_CID_MPEG_BASE+379) -#define V4L2_CID_MPEG_VIDEO_H264_HIERARCHICAL_CODING_TYPE (V4L2_CID_MPEG_BASE+380) -enum v4l2_mpeg_video_h264_hierarchical_coding_type { - V4L2_MPEG_VIDEO_H264_HIERARCHICAL_CODING_B = 0, - V4L2_MPEG_VIDEO_H264_HIERARCHICAL_CODING_P = 1, -}; -#define V4L2_CID_MPEG_VIDEO_H264_HIERARCHICAL_CODING_LAYER (V4L2_CID_MPEG_BASE+381) -#define V4L2_CID_MPEG_VIDEO_H264_HIERARCHICAL_CODING_LAYER_QP (V4L2_CID_MPEG_BASE+382) -#define V4L2_CID_MPEG_VIDEO_MPEG4_I_FRAME_QP (V4L2_CID_MPEG_BASE+400) -#define V4L2_CID_MPEG_VIDEO_MPEG4_P_FRAME_QP (V4L2_CID_MPEG_BASE+401) -#define V4L2_CID_MPEG_VIDEO_MPEG4_B_FRAME_QP (V4L2_CID_MPEG_BASE+402) -#define V4L2_CID_MPEG_VIDEO_MPEG4_MIN_QP (V4L2_CID_MPEG_BASE+403) -#define V4L2_CID_MPEG_VIDEO_MPEG4_MAX_QP (V4L2_CID_MPEG_BASE+404) -#define V4L2_CID_MPEG_VIDEO_MPEG4_LEVEL (V4L2_CID_MPEG_BASE+405) -enum v4l2_mpeg_video_mpeg4_level { - V4L2_MPEG_VIDEO_MPEG4_LEVEL_0 = 0, - V4L2_MPEG_VIDEO_MPEG4_LEVEL_0B = 1, - V4L2_MPEG_VIDEO_MPEG4_LEVEL_1 = 2, - V4L2_MPEG_VIDEO_MPEG4_LEVEL_2 = 3, - V4L2_MPEG_VIDEO_MPEG4_LEVEL_3 = 4, - V4L2_MPEG_VIDEO_MPEG4_LEVEL_3B = 5, - V4L2_MPEG_VIDEO_MPEG4_LEVEL_4 = 6, - V4L2_MPEG_VIDEO_MPEG4_LEVEL_5 = 7, -}; -#define V4L2_CID_MPEG_VIDEO_MPEG4_PROFILE (V4L2_CID_MPEG_BASE+406) -enum v4l2_mpeg_video_mpeg4_profile { - V4L2_MPEG_VIDEO_MPEG4_PROFILE_SIMPLE = 0, - V4L2_MPEG_VIDEO_MPEG4_PROFILE_ADVANCED_SIMPLE = 1, - V4L2_MPEG_VIDEO_MPEG4_PROFILE_CORE = 2, - V4L2_MPEG_VIDEO_MPEG4_PROFILE_SIMPLE_SCALABLE = 3, - V4L2_MPEG_VIDEO_MPEG4_PROFILE_ADVANCED_CODING_EFFICIENCY = 4, -}; -#define V4L2_CID_MPEG_VIDEO_MPEG4_QPEL (V4L2_CID_MPEG_BASE+407) - -/* Control IDs for VP8 streams - * Although VP8 is not part of MPEG we add these controls to the MPEG class - * as that class is already handling other video compression standards - */ -#define V4L2_CID_MPEG_VIDEO_VPX_NUM_PARTITIONS (V4L2_CID_MPEG_BASE+500) -enum v4l2_vp8_num_partitions { - V4L2_CID_MPEG_VIDEO_VPX_1_PARTITION = 0, - V4L2_CID_MPEG_VIDEO_VPX_2_PARTITIONS = 1, - V4L2_CID_MPEG_VIDEO_VPX_4_PARTITIONS = 2, - V4L2_CID_MPEG_VIDEO_VPX_8_PARTITIONS = 3, -}; -#define V4L2_CID_MPEG_VIDEO_VPX_IMD_DISABLE_4X4 (V4L2_CID_MPEG_BASE+501) -#define V4L2_CID_MPEG_VIDEO_VPX_NUM_REF_FRAMES (V4L2_CID_MPEG_BASE+502) -enum v4l2_vp8_num_ref_frames { - V4L2_CID_MPEG_VIDEO_VPX_1_REF_FRAME = 0, - V4L2_CID_MPEG_VIDEO_VPX_2_REF_FRAME = 1, - V4L2_CID_MPEG_VIDEO_VPX_3_REF_FRAME = 2, -}; -#define V4L2_CID_MPEG_VIDEO_VPX_FILTER_LEVEL (V4L2_CID_MPEG_BASE+503) -#define V4L2_CID_MPEG_VIDEO_VPX_FILTER_SHARPNESS (V4L2_CID_MPEG_BASE+504) -#define V4L2_CID_MPEG_VIDEO_VPX_GOLDEN_FRAME_REF_PERIOD (V4L2_CID_MPEG_BASE+505) -#define V4L2_CID_MPEG_VIDEO_VPX_GOLDEN_FRAME_SEL (V4L2_CID_MPEG_BASE+506) -enum v4l2_vp8_golden_frame_sel { - V4L2_CID_MPEG_VIDEO_VPX_GOLDEN_FRAME_USE_PREV = 0, - V4L2_CID_MPEG_VIDEO_VPX_GOLDEN_FRAME_USE_REF_PERIOD = 1, -}; -#define V4L2_CID_MPEG_VIDEO_VPX_MIN_QP (V4L2_CID_MPEG_BASE+507) -#define V4L2_CID_MPEG_VIDEO_VPX_MAX_QP (V4L2_CID_MPEG_BASE+508) -#define V4L2_CID_MPEG_VIDEO_VPX_I_FRAME_QP (V4L2_CID_MPEG_BASE+509) -#define V4L2_CID_MPEG_VIDEO_VPX_P_FRAME_QP (V4L2_CID_MPEG_BASE+510) -#define V4L2_CID_MPEG_VIDEO_VPX_PROFILE (V4L2_CID_MPEG_BASE+511) - -/* MPEG-class control IDs specific to the CX2341x driver as defined by V4L2 */ -#define V4L2_CID_MPEG_CX2341X_BASE (V4L2_CTRL_CLASS_MPEG | 0x1000) -#define V4L2_CID_MPEG_CX2341X_VIDEO_SPATIAL_FILTER_MODE (V4L2_CID_MPEG_CX2341X_BASE+0) -enum v4l2_mpeg_cx2341x_video_spatial_filter_mode { - V4L2_MPEG_CX2341X_VIDEO_SPATIAL_FILTER_MODE_MANUAL = 0, - V4L2_MPEG_CX2341X_VIDEO_SPATIAL_FILTER_MODE_AUTO = 1, -}; -#define V4L2_CID_MPEG_CX2341X_VIDEO_SPATIAL_FILTER (V4L2_CID_MPEG_CX2341X_BASE+1) -#define V4L2_CID_MPEG_CX2341X_VIDEO_LUMA_SPATIAL_FILTER_TYPE (V4L2_CID_MPEG_CX2341X_BASE+2) -enum v4l2_mpeg_cx2341x_video_luma_spatial_filter_type { - V4L2_MPEG_CX2341X_VIDEO_LUMA_SPATIAL_FILTER_TYPE_OFF = 0, - V4L2_MPEG_CX2341X_VIDEO_LUMA_SPATIAL_FILTER_TYPE_1D_HOR = 1, - V4L2_MPEG_CX2341X_VIDEO_LUMA_SPATIAL_FILTER_TYPE_1D_VERT = 2, - V4L2_MPEG_CX2341X_VIDEO_LUMA_SPATIAL_FILTER_TYPE_2D_HV_SEPARABLE = 3, - V4L2_MPEG_CX2341X_VIDEO_LUMA_SPATIAL_FILTER_TYPE_2D_SYM_NON_SEPARABLE = 4, -}; -#define V4L2_CID_MPEG_CX2341X_VIDEO_CHROMA_SPATIAL_FILTER_TYPE (V4L2_CID_MPEG_CX2341X_BASE+3) -enum v4l2_mpeg_cx2341x_video_chroma_spatial_filter_type { - V4L2_MPEG_CX2341X_VIDEO_CHROMA_SPATIAL_FILTER_TYPE_OFF = 0, - V4L2_MPEG_CX2341X_VIDEO_CHROMA_SPATIAL_FILTER_TYPE_1D_HOR = 1, -}; -#define V4L2_CID_MPEG_CX2341X_VIDEO_TEMPORAL_FILTER_MODE (V4L2_CID_MPEG_CX2341X_BASE+4) -enum v4l2_mpeg_cx2341x_video_temporal_filter_mode { - V4L2_MPEG_CX2341X_VIDEO_TEMPORAL_FILTER_MODE_MANUAL = 0, - V4L2_MPEG_CX2341X_VIDEO_TEMPORAL_FILTER_MODE_AUTO = 1, -}; -#define V4L2_CID_MPEG_CX2341X_VIDEO_TEMPORAL_FILTER (V4L2_CID_MPEG_CX2341X_BASE+5) -#define V4L2_CID_MPEG_CX2341X_VIDEO_MEDIAN_FILTER_TYPE (V4L2_CID_MPEG_CX2341X_BASE+6) -enum v4l2_mpeg_cx2341x_video_median_filter_type { - V4L2_MPEG_CX2341X_VIDEO_MEDIAN_FILTER_TYPE_OFF = 0, - V4L2_MPEG_CX2341X_VIDEO_MEDIAN_FILTER_TYPE_HOR = 1, - V4L2_MPEG_CX2341X_VIDEO_MEDIAN_FILTER_TYPE_VERT = 2, - V4L2_MPEG_CX2341X_VIDEO_MEDIAN_FILTER_TYPE_HOR_VERT = 3, - V4L2_MPEG_CX2341X_VIDEO_MEDIAN_FILTER_TYPE_DIAG = 4, -}; -#define V4L2_CID_MPEG_CX2341X_VIDEO_LUMA_MEDIAN_FILTER_BOTTOM (V4L2_CID_MPEG_CX2341X_BASE+7) -#define V4L2_CID_MPEG_CX2341X_VIDEO_LUMA_MEDIAN_FILTER_TOP (V4L2_CID_MPEG_CX2341X_BASE+8) -#define V4L2_CID_MPEG_CX2341X_VIDEO_CHROMA_MEDIAN_FILTER_BOTTOM (V4L2_CID_MPEG_CX2341X_BASE+9) -#define V4L2_CID_MPEG_CX2341X_VIDEO_CHROMA_MEDIAN_FILTER_TOP (V4L2_CID_MPEG_CX2341X_BASE+10) -#define V4L2_CID_MPEG_CX2341X_STREAM_INSERT_NAV_PACKETS (V4L2_CID_MPEG_CX2341X_BASE+11) - -/* MPEG-class control IDs specific to the Samsung MFC 5.1 driver as defined by V4L2 */ -#define V4L2_CID_MPEG_MFC51_BASE (V4L2_CTRL_CLASS_MPEG | 0x1100) - -#define V4L2_CID_MPEG_MFC51_VIDEO_DECODER_H264_DISPLAY_DELAY (V4L2_CID_MPEG_MFC51_BASE+0) -#define V4L2_CID_MPEG_MFC51_VIDEO_DECODER_H264_DISPLAY_DELAY_ENABLE (V4L2_CID_MPEG_MFC51_BASE+1) -#define V4L2_CID_MPEG_MFC51_VIDEO_FRAME_SKIP_MODE (V4L2_CID_MPEG_MFC51_BASE+2) -enum v4l2_mpeg_mfc51_video_frame_skip_mode { - V4L2_MPEG_MFC51_VIDEO_FRAME_SKIP_MODE_DISABLED = 0, - V4L2_MPEG_MFC51_VIDEO_FRAME_SKIP_MODE_LEVEL_LIMIT = 1, - V4L2_MPEG_MFC51_VIDEO_FRAME_SKIP_MODE_BUF_LIMIT = 2, -}; -#define V4L2_CID_MPEG_MFC51_VIDEO_FORCE_FRAME_TYPE (V4L2_CID_MPEG_MFC51_BASE+3) -enum v4l2_mpeg_mfc51_video_force_frame_type { - V4L2_MPEG_MFC51_VIDEO_FORCE_FRAME_TYPE_DISABLED = 0, - V4L2_MPEG_MFC51_VIDEO_FORCE_FRAME_TYPE_I_FRAME = 1, - V4L2_MPEG_MFC51_VIDEO_FORCE_FRAME_TYPE_NOT_CODED = 2, -}; -#define V4L2_CID_MPEG_MFC51_VIDEO_PADDING (V4L2_CID_MPEG_MFC51_BASE+4) -#define V4L2_CID_MPEG_MFC51_VIDEO_PADDING_YUV (V4L2_CID_MPEG_MFC51_BASE+5) -#define V4L2_CID_MPEG_MFC51_VIDEO_RC_FIXED_TARGET_BIT (V4L2_CID_MPEG_MFC51_BASE+6) -#define V4L2_CID_MPEG_MFC51_VIDEO_RC_REACTION_COEFF (V4L2_CID_MPEG_MFC51_BASE+7) -#define V4L2_CID_MPEG_MFC51_VIDEO_H264_ADAPTIVE_RC_ACTIVITY (V4L2_CID_MPEG_MFC51_BASE+50) -#define V4L2_CID_MPEG_MFC51_VIDEO_H264_ADAPTIVE_RC_DARK (V4L2_CID_MPEG_MFC51_BASE+51) -#define V4L2_CID_MPEG_MFC51_VIDEO_H264_ADAPTIVE_RC_SMOOTH (V4L2_CID_MPEG_MFC51_BASE+52) -#define V4L2_CID_MPEG_MFC51_VIDEO_H264_ADAPTIVE_RC_STATIC (V4L2_CID_MPEG_MFC51_BASE+53) -#define V4L2_CID_MPEG_MFC51_VIDEO_H264_NUM_REF_PIC_FOR_P (V4L2_CID_MPEG_MFC51_BASE+54) - -/* MPEG-class control IDs specific to the msm_vidc driver */ -#define V4L2_CID_MPEG_MSM_VIDC_BASE (V4L2_CTRL_CLASS_MPEG | 0x2000) - -#define V4L2_CID_MPEG_VIDC_VIDEO_PICTYPE_DEC_MODE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE+0) -enum v4l2_mpeg_vidc_video_pictype_dec_mode { - V4L2_MPEG_VIDC_VIDEO_PICTYPE_DECODE_OFF = 0, - V4L2_MPEG_VIDC_VIDEO_PICTYPE_DECODE_ON = 1, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_KEEP_ASPECT_RATIO \ - (V4L2_CID_MPEG_MSM_VIDC_BASE+1) - -#define V4L2_CID_MPEG_VIDC_VIDEO_STREAM_FORMAT (V4L2_CID_MPEG_MSM_VIDC_BASE+2) -enum v4l2_mpeg_vidc_video_stream_format { - V4L2_MPEG_VIDC_VIDEO_NAL_FORMAT_STARTCODES = 0, - V4L2_MPEG_VIDC_VIDEO_NAL_FORMAT_ONE_NAL_PER_BUFFER = 1, - V4L2_MPEG_VIDC_VIDEO_NAL_FORMAT_ONE_BYTE_LENGTH = 2, - V4L2_MPEG_VIDC_VIDEO_NAL_FORMAT_TWO_BYTE_LENGTH = 3, - V4L2_MPEG_VIDC_VIDEO_NAL_FORMAT_FOUR_BYTE_LENGTH = 4, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_OUTPUT_ORDER (V4L2_CID_MPEG_MSM_VIDC_BASE+3) -enum v4l2_mpeg_vidc_video_output_order { - V4L2_MPEG_VIDC_VIDEO_OUTPUT_ORDER_DISPLAY = 0, - V4L2_MPEG_VIDC_VIDEO_OUTPUT_ORDER_DECODE = 1, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_FRAME_RATE (V4L2_CID_MPEG_MSM_VIDC_BASE+4) -#define V4L2_CID_MPEG_VIDC_VIDEO_IDR_PERIOD (V4L2_CID_MPEG_MSM_VIDC_BASE+5) -#define V4L2_CID_MPEG_VIDC_VIDEO_NUM_P_FRAMES (V4L2_CID_MPEG_MSM_VIDC_BASE+6) -#define V4L2_CID_MPEG_VIDC_VIDEO_NUM_B_FRAMES (V4L2_CID_MPEG_MSM_VIDC_BASE+7) -#define V4L2_CID_MPEG_VIDC_VIDEO_REQUEST_IFRAME (V4L2_CID_MPEG_MSM_VIDC_BASE+8) - -#define V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL (V4L2_CID_MPEG_MSM_VIDC_BASE+9) -enum v4l2_mpeg_vidc_video_rate_control { - V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_OFF = 0, - V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_VBR_VFR = 1, - V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_VBR_CFR = 2, - V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_CBR_VFR = 3, - V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_CBR_CFR = 4, - V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_MBR_CFR = 5, - V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_MBR_VFR = 6, - V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_CQ = 7, -}; -#define V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_MBR_CFR \ - V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_MBR_CFR -#define V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_MBR_VFR \ - V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_MBR_VFR - -#define V4L2_CID_MPEG_VIDC_VIDEO_ROTATION (V4L2_CID_MPEG_MSM_VIDC_BASE+10) -enum v4l2_mpeg_vidc_video_rotation { - V4L2_CID_MPEG_VIDC_VIDEO_ROTATION_NONE = 0, - V4L2_CID_MPEG_VIDC_VIDEO_ROTATION_90 = 1, - V4L2_CID_MPEG_VIDC_VIDEO_ROTATION_180 = 2, - V4L2_CID_MPEG_VIDC_VIDEO_ROTATION_270 = 3, -}; -#define V4L2_CID_MPEG_VIDC_VIDEO_H264_CABAC_MODEL \ - (V4L2_CID_MPEG_MSM_VIDC_BASE+11) -enum v4l2_mpeg_vidc_h264_cabac_model { - V4L2_CID_MPEG_VIDC_VIDEO_H264_CABAC_MODEL_0 = 0, - V4L2_CID_MPEG_VIDC_VIDEO_H264_CABAC_MODEL_1 = 1, - V4L2_CID_MPEG_VIDC_VIDEO_H264_CABAC_MODEL_2 = 2, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_INTRA_REFRESH_MODE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE+12) -enum v4l2_mpeg_vidc_video_intra_refresh_mode { - V4L2_CID_MPEG_VIDC_VIDEO_INTRA_REFRESH_NONE = 0, - V4L2_CID_MPEG_VIDC_VIDEO_INTRA_REFRESH_CYCLIC = 1, - V4L2_CID_MPEG_VIDC_VIDEO_INTRA_REFRESH_RANDOM = 2, - V4L2_CID_MPEG_VIDC_VIDEO_INTRA_REFRESH_ADAPTIVE = 3, - V4L2_CID_MPEG_VIDC_VIDEO_INTRA_REFRESH_CYCLIC_ADAPTIVE = 4, -}; -#define V4L2_CID_MPEG_VIDC_VIDEO_IR_MBS (V4L2_CID_MPEG_MSM_VIDC_BASE+13) - -#define V4L2_CID_MPEG_VIDC_VIDEO_AU_DELIMITER \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 14) -enum v4l2_mpeg_vidc_video_au_delimiter { - V4L2_MPEG_VIDC_VIDEO_AU_DELIMITER_DISABLED = 0, - V4L2_MPEG_VIDC_VIDEO_AU_DELIMITER_ENABLED = 1 -}; -#define V4L2_CID_MPEG_VIDC_VIDEO_SYNC_FRAME_DECODE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 15) -enum v4l2_mpeg_vidc_video_sync_frame_decode { - V4L2_MPEG_VIDC_VIDEO_SYNC_FRAME_DECODE_DISABLE = 0, - V4L2_MPEG_VIDC_VIDEO_SYNC_FRAME_DECODE_ENABLE = 1 -}; -#define V4L2_CID_MPEG_VIDC_VIDEO_SECURE (V4L2_CID_MPEG_MSM_VIDC_BASE+16) -#define V4L2_CID_MPEG_VIDC_VIDEO_EXTRADATA \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 17) -enum v4l2_mpeg_vidc_extradata { - V4L2_MPEG_VIDC_EXTRADATA_NONE = 0, - V4L2_MPEG_VIDC_EXTRADATA_MB_QUANTIZATION = 1, - V4L2_MPEG_VIDC_EXTRADATA_INTERLACE_VIDEO = 2, - V4L2_MPEG_VIDC_EXTRADATA_VC1_FRAMEDISP = 3, - V4L2_MPEG_VIDC_EXTRADATA_VC1_SEQDISP = 4, - V4L2_MPEG_VIDC_EXTRADATA_TIMESTAMP = 5, - V4L2_MPEG_VIDC_EXTRADATA_S3D_FRAME_PACKING = 6, - V4L2_MPEG_VIDC_EXTRADATA_FRAME_RATE = 7, - V4L2_MPEG_VIDC_EXTRADATA_PANSCAN_WINDOW = 8, - V4L2_MPEG_VIDC_EXTRADATA_RECOVERY_POINT_SEI = 9, - V4L2_MPEG_VIDC_EXTRADATA_MULTISLICE_INFO = 10, - V4L2_MPEG_VIDC_EXTRADATA_NUM_CONCEALED_MB = 11, - V4L2_MPEG_VIDC_EXTRADATA_METADATA_FILLER = 12, - V4L2_MPEG_VIDC_EXTRADATA_INPUT_CROP = 13, - V4L2_MPEG_VIDC_EXTRADATA_DIGITAL_ZOOM = 14, - V4L2_MPEG_VIDC_EXTRADATA_ASPECT_RATIO = 15, - V4L2_MPEG_VIDC_EXTRADATA_MPEG2_SEQDISP = 16, - V4L2_MPEG_VIDC_EXTRADATA_STREAM_USERDATA = 17, - V4L2_MPEG_VIDC_EXTRADATA_FRAME_QP = 18, - V4L2_MPEG_VIDC_EXTRADATA_FRAME_BITS_INFO = 19, - V4L2_MPEG_VIDC_EXTRADATA_LTR = 20, - V4L2_MPEG_VIDC_EXTRADATA_METADATA_MBI = 21, - V4L2_MPEG_VIDC_EXTRADATA_VQZIP_SEI = 22, - V4L2_MPEG_VIDC_EXTRADATA_YUV_STATS = 23, - V4L2_MPEG_VIDC_EXTRADATA_ROI_QP = 24, -#define V4L2_MPEG_VIDC_EXTRADATA_OUTPUT_CROP \ - V4L2_MPEG_VIDC_EXTRADATA_OUTPUT_CROP - V4L2_MPEG_VIDC_EXTRADATA_OUTPUT_CROP = 25, -#define V4L2_MPEG_VIDC_EXTRADATA_DISPLAY_COLOUR_SEI \ - V4L2_MPEG_VIDC_EXTRADATA_DISPLAY_COLOUR_SEI - V4L2_MPEG_VIDC_EXTRADATA_DISPLAY_COLOUR_SEI = 26, -#define V4L2_MPEG_VIDC_EXTRADATA_CONTENT_LIGHT_LEVEL_SEI \ - V4L2_MPEG_VIDC_EXTRADATA_CONTENT_LIGHT_LEVEL_SEI - V4L2_MPEG_VIDC_EXTRADATA_CONTENT_LIGHT_LEVEL_SEI = 27, -#define V4L2_MPEG_VIDC_EXTRADATA_PQ_INFO \ - V4L2_MPEG_VIDC_EXTRADATA_PQ_INFO - V4L2_MPEG_VIDC_EXTRADATA_PQ_INFO = 28, -#define V4L2_MPEG_VIDC_EXTRADATA_VUI_DISPLAY \ - V4L2_MPEG_VIDC_EXTRADATA_VUI_DISPLAY - V4L2_MPEG_VIDC_EXTRADATA_VUI_DISPLAY = 29, -#define V4L2_MPEG_VIDC_EXTRADATA_VPX_COLORSPACE \ - V4L2_MPEG_VIDC_EXTRADATA_VPX_COLORSPACE - V4L2_MPEG_VIDC_EXTRADATA_VPX_COLORSPACE = 30, -#define V4L2_MPEG_VIDC_EXTRADATA_UBWC_CR_STATS_INFO \ - V4L2_MPEG_VIDC_EXTRADATA_UBWC_CR_STATS_INFO - V4L2_MPEG_VIDC_EXTRADATA_UBWC_CR_STATS_INFO = 31, -#define V4L2_MPEG_VIDC_EXTRADATA_ENC_FRAME_QP \ - V4L2_MPEG_VIDC_EXTRADATA_ENC_FRAME_QP - V4L2_MPEG_VIDC_EXTRADATA_ENC_FRAME_QP = 32, -}; - -#define V4L2_CID_MPEG_VIDEO_MULTI_SLICE_DELIVERY_MODE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 18) - -#define V4L2_CID_MPEG_VIDC_VIDEO_VUI_TIMING_INFO \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 19) -enum v4l2_mpeg_vidc_video_vui_timing_info { - V4L2_MPEG_VIDC_VIDEO_VUI_TIMING_INFO_DISABLED = 0, - V4L2_MPEG_VIDC_VIDEO_VUI_TIMING_INFO_ENABLED = 1 -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_VP8_PROFILE_LEVEL \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 20) -enum v4l2_mpeg_vidc_video_vp8_profile_level { - V4L2_MPEG_VIDC_VIDEO_VP8_UNUSED, - V4L2_MPEG_VIDC_VIDEO_VP8_VERSION_0, - V4L2_MPEG_VIDC_VIDEO_VP8_VERSION_1, - V4L2_MPEG_VIDC_VIDEO_VP8_VERSION_2, - V4L2_MPEG_VIDC_VIDEO_VP8_VERSION_3, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_PRESERVE_TEXT_QUALITY \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 21) -enum v4l2_mpeg_vidc_video_preserve_text_quality { - V4L2_MPEG_VIDC_VIDEO_PRESERVE_TEXT_QUALITY_DISABLED = 0, - V4L2_MPEG_VIDC_VIDEO_PRESERVE_TEXT_QUALITY_ENABLED = 1 -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_STREAM_OUTPUT_MODE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 22) -enum v4l2_mpeg_vidc_video_decoder_multi_stream { - V4L2_CID_MPEG_VIDC_VIDEO_STREAM_OUTPUT_PRIMARY = 0, - V4L2_CID_MPEG_VIDC_VIDEO_STREAM_OUTPUT_SECONDARY = 1, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_MPEG2_LEVEL (V4L2_CID_MPEG_MSM_VIDC_BASE+23) -enum v4l2_mpeg_vidc_video_mpeg2_level { - V4L2_MPEG_VIDC_VIDEO_MPEG2_LEVEL_0 = 0, - V4L2_MPEG_VIDC_VIDEO_MPEG2_LEVEL_1 = 1, - V4L2_MPEG_VIDC_VIDEO_MPEG2_LEVEL_2 = 2, - V4L2_MPEG_VIDC_VIDEO_MPEG2_LEVEL_3 = 3, -}; -#define V4L2_CID_MPEG_VIDC_VIDEO_MPEG2_PROFILE (V4L2_CID_MPEG_MSM_VIDC_BASE+24) -enum v4l2_mpeg_vidc_video_mpeg2_profile { - V4L2_MPEG_VIDC_VIDEO_MPEG2_PROFILE_SIMPLE = 0, - V4L2_MPEG_VIDC_VIDEO_MPEG2_PROFILE_MAIN = 1, - V4L2_MPEG_VIDC_VIDEO_MPEG2_PROFILE_422 = 2, - V4L2_MPEG_VIDC_VIDEO_MPEG2_PROFILE_SNR_SCALABLE = 3, - V4L2_MPEG_VIDC_VIDEO_MPEG2_PROFILE_SPATIAL_SCALABLE = 4, - V4L2_MPEG_VIDC_VIDEO_MPEG2_PROFILE_HIGH = 5, -}; - -enum v4l2_mpeg_vidc_video_mvc_layout { - V4L2_MPEG_VIDC_VIDEO_MVC_SEQUENTIAL = 0, - V4L2_MPEG_VIDC_VIDEO_MVC_TOP_BOTTOM = 1 -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_CONCEAL_COLOR \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 25) - -#define V4L2_CID_MPEG_VIDC_VIDEO_LTRMODE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 26) - -enum v4l2_mpeg_vidc_video_ltrmode { - V4L2_MPEG_VIDC_VIDEO_LTR_MODE_DISABLE = 0, - V4L2_MPEG_VIDC_VIDEO_LTR_MODE_MANUAL = 1, - V4L2_MPEG_VIDC_VIDEO_LTR_MODE_PERIODIC = 2 -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_LTRCOUNT \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 27) - -#define V4L2_CID_MPEG_VIDC_VIDEO_USELTRFRAME \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 28) - -#define V4L2_CID_MPEG_VIDC_VIDEO_MARKLTRFRAME \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 29) - -#define V4L2_CID_MPEG_VIDC_VIDEO_HIER_P_NUM_LAYERS \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 30) - -#define V4L2_CID_MPEG_VIDC_VIDEO_ALLOC_MODE_OUTPUT \ - (V4L2_CID_MPEG_MSM_VIDC_BASE+31) -enum v4l2_mpeg_vidc_video_alloc_mode_type { - V4L2_MPEG_VIDC_VIDEO_STATIC = 0, - V4L2_MPEG_VIDC_VIDEO_RING = 1, - V4L2_MPEG_VIDC_VIDEO_DYNAMIC = 2, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_IFRAME_X_RANGE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 32) - -#define V4L2_CID_MPEG_VIDC_VIDEO_PFRAME_X_RANGE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 33) - -#define V4L2_CID_MPEG_VIDC_VIDEO_BFRAME_X_RANGE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 34) - -#define V4L2_CID_MPEG_VIDC_VIDEO_IFRAME_Y_RANGE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 35) - -#define V4L2_CID_MPEG_VIDC_VIDEO_PFRAME_Y_RANGE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 36) - -#define V4L2_CID_MPEG_VIDC_VIDEO_BFRAME_Y_RANGE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 37) - -#define V4L2_CID_MPEG_VIDC_VIDEO_VPX_ERROR_RESILIENCE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 38) - -#define V4L2_CID_MPEG_VIDC_VIDEO_BUFFER_SIZE_LIMIT \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 39) - -enum vl42_mpeg_vidc_video_vpx_error_resilience { - V4L2_MPEG_VIDC_VIDEO_VPX_ERROR_RESILIENCE_DISABLED = 0, - V4L2_MPEG_VIDC_VIDEO_VPX_ERROR_RESILIENCE_ENABLED = 1, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_HEVC_PROFILE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 40) -enum v4l2_mpeg_video_hevc_profile { - V4L2_MPEG_VIDC_VIDEO_HEVC_PROFILE_MAIN = 0, - V4L2_MPEG_VIDC_VIDEO_HEVC_PROFILE_MAIN10 = 1, - V4L2_MPEG_VIDC_VIDEO_HEVC_PROFILE_MAIN_STILL_PIC = 2, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_HEVC_TIER_LEVEL \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 41) -enum v4l2_mpeg_video_hevc_level { - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_1 = 0, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_1 = 1, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_2 = 2, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_2 = 3, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_2_1 = 4, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_2_1 = 5, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_3 = 6, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_3 = 7, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_3_1 = 8, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_3_1 = 9, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_4 = 10, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_4 = 11, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_4_1 = 12, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_4_1 = 13, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_5 = 14, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_5 = 15, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_5_1 = 16, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_5_1 = 17, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_5_2 = 18, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_5_2 = 19, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_6 = 20, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_6 = 21, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_6_1 = 22, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_6_1 = 23, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_6_2 = 24, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_6_2 = 25, -#define V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_UNKNOWN \ - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_UNKNOWN - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_UNKNOWN = 26, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_HIER_B_NUM_LAYERS \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 42) - -#define V4L2_CID_MPEG_VIDC_VIDEO_HYBRID_HIERP_MODE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 43) - -#define V4L2_CID_MPEG_VIDC_VIDEO_DPB_COLOR_FORMAT \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 44) - -enum v4l2_mpeg_vidc_video_dpb_color_format { - V4L2_MPEG_VIDC_VIDEO_DPB_COLOR_FMT_NONE = 0, - V4L2_MPEG_VIDC_VIDEO_DPB_COLOR_FMT_UBWC = 1, - V4L2_MPEG_VIDC_VIDEO_DPB_COLOR_FMT_TP10_UBWC = 2 -}; - -#define V4L2_CID_VIDC_QBUF_MODE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 45) -enum v4l2_vidc_qbuf_mode { - V4L2_VIDC_QBUF_STANDARD = 0, - V4L2_VIDC_QBUF_BATCHED = 1, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_MAX_HIERP_LAYERS \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 46) - -#define V4L2_CID_MPEG_VIDC_VIDEO_BASELAYER_ID \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 47) - -#define V4L2_CID_MPEG_VIDC_VENC_PARAM_SAR_WIDTH \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 48) - -#define V4L2_CID_MPEG_VIDC_VENC_PARAM_SAR_HEIGHT \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 49) - -#define V4L2_CID_MPEG_VIDC_VIDEO_VQZIP_SEI \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 50) - -enum v4l2_mpeg_vidc_video_vqzip_sei_enable { - V4L2_CID_MPEG_VIDC_VIDEO_VQZIP_SEI_DISABLE = 0, - V4L2_CID_MPEG_VIDC_VIDEO_VQZIP_SEI_ENABLE = 1 -}; - -#define V4L2_CID_MPEG_VIDC_VENC_PARAM_LAYER_BITRATE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 51) - -#define V4L2_CID_MPEG_VIDC_VIDEO_PRIORITY \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 52) - -enum v4l2_mpeg_vidc_video_priority { - V4L2_MPEG_VIDC_VIDEO_PRIORITY_REALTIME_ENABLE = 0, - V4L2_MPEG_VIDC_VIDEO_PRIORITY_REALTIME_DISABLE = 1, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_OPERATING_RATE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 53) - -#define V4L2_CID_MPEG_VIDC_VIDEO_VENC_BITRATE_TYPE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 54) - -enum v4l2_mpeg_vidc_video_venc_bitrate_type_enable { - V4L2_CID_MPEG_VIDC_VIDEO_VENC_BITRATE_DISABLE = 0, - V4L2_CID_MPEG_VIDC_VIDEO_VENC_BITRATE_ENABLE = 1 -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_VPE_CSC \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 55) - -enum v4l2_cid_mpeg_vidc_video_vpe_csc_type_enable { - V4L2_CID_MPEG_VIDC_VIDEO_VPE_CSC_DISABLE = 0, - V4L2_CID_MPEG_VIDC_VIDEO_VPE_CSC_ENABLE = 1 -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_LOWLATENCY_MODE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 56) - -enum v4l2_mpeg_vidc_video_lowlatency_mode { - V4L2_CID_MPEG_VIDC_VIDEO_LOWLATENCY_DISABLE = 0, - V4L2_CID_MPEG_VIDC_VIDEO_LOWLATENCY_ENABLE = 1, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_BLUR_WIDTH \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 57) - -#define V4L2_CID_MPEG_VIDC_VIDEO_BLUR_HEIGHT \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 58) - -#define V4L2_CID_MPEG_VIDC_VIDEO_H264_TRANSFORM_8x8 \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 59) -enum v4l2_mpeg_vidc_video_h264_transform_8x8 { - V4L2_MPEG_VIDC_VIDEO_H264_TRANSFORM_8x8_DISABLE = 0, - V4L2_MPEG_VIDC_VIDEO_H264_TRANSFORM_8x8_ENABLE = 1, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_COLOR_SPACE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 60) - -#define V4L2_CID_MPEG_VIDC_VIDEO_FULL_RANGE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 61) - -enum v4l2_cid_mpeg_vidc_video_full_range { - V4L2_CID_MPEG_VIDC_VIDEO_FULL_RANGE_DISABLE = 0, - V4L2_CID_MPEG_VIDC_VIDEO_FULL_RANGE_ENABLE = 1, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_TRANSFER_CHARS \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 62) - -#define V4L2_CID_MPEG_VIDC_VIDEO_MATRIX_COEFFS \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 63) - -#define V4L2_CID_MPEG_VIDC_VIDEO_IFRAME_SIZE_TYPE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 64) - -#define V4L2_CID_MPEG_VIDC_VIDEO_LAYER_ID \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 65) - -#define V4L2_CID_MPEG_VIDC_VIDEO_VP9_PROFILE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 66) -enum v4l2_mpeg_vidc_video_vp9_profile { - V4L2_MPEG_VIDC_VIDEO_VP9_PROFILE_UNUSED = 0, - V4L2_MPEG_VIDC_VIDEO_VP9_PROFILE_P0 = 1, - V4L2_MPEG_VIDC_VIDEO_VP9_PROFILE_P2_10 = 2, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_VP9_LEVEL \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 67) -enum v4l2_mpeg_vidc_video_vp9_level { - V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_UNUSED = 0, - V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_1 = 1, - V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_11 = 2, - V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_2 = 3, - V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_21 = 4, - V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_3 = 5, - V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_31 = 6, - V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_4 = 7, - V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_41 = 8, - V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_5 = 9, - V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_51 = 10, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_MB_ERROR_MAP_REPORTING \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 68) -#define V4L2_CID_MPEG_VIDC_VIDEO_CONTINUE_DATA_TRANSFER \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 69) - -#define V4L2_CID_MPEG_VIDC_VIDEO_ALLOC_MODE_INPUT \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 70) - -#define V4L2_CID_MPEG_VIDC_VIDEO_FRAME_ASSEMBLY \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 71) -enum v4l2_mpeg_vidc_video_assembly { - V4L2_MPEG_VIDC_FRAME_ASSEMBLY_DISABLE = 0, - V4L2_MPEG_VIDC_FRAME_ASSEMBLY_ENABLE = 1, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_H263_PROFILE\ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 72) -enum v4l2_mpeg_vidc_video_h263_profile { - V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_BASELINE = 0, - V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_H320CODING = 1, - V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_BACKWARDCOMPATIBLE = 2, - V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_ISWV2 = 3, - V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_ISWV3 = 4, - V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_HIGHCOMPRESSION = 5, - V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_INTERNET = 6, - V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_INTERLACE = 7, - V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_HIGHLATENCY = 8, -}; - -#define V4L2_CID_MPEG_VIDEO_MIN_QP_PACKED \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 97) -#define V4L2_CID_MPEG_VIDEO_MAX_QP_PACKED \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 98) -#define V4L2_CID_MPEG_VIDC_VIDEO_I_FRAME_QP \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 99) -#define V4L2_CID_MPEG_VIDC_VIDEO_P_FRAME_QP \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 100) -#define V4L2_CID_MPEG_VIDC_VIDEO_B_FRAME_QP \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 101) -#define V4L2_CID_MPEG_VIDC_VIDEO_I_FRAME_QP_MIN \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 102) -#define V4L2_CID_MPEG_VIDC_VIDEO_P_FRAME_QP_MIN \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 103) -#define V4L2_CID_MPEG_VIDC_VIDEO_B_FRAME_QP_MIN \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 104) -#define V4L2_CID_MPEG_VIDC_VIDEO_I_FRAME_QP_MAX \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 105) -#define V4L2_CID_MPEG_VIDC_VIDEO_P_FRAME_QP_MAX \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 106) -#define V4L2_CID_MPEG_VIDC_VIDEO_B_FRAME_QP_MAX \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 107) -#define V4L2_CID_MPEG_VIDC_VIDEO_QP_MASK \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 108) - -enum v4l2_mpeg_vidc_video_venc_iframesize_type { - V4L2_CID_MPEG_VIDC_VIDEO_IFRAME_SIZE_DEFAULT, - V4L2_CID_MPEG_VIDC_VIDEO_IFRAME_SIZE_MEDIUM, - V4L2_CID_MPEG_VIDC_VIDEO_IFRAME_SIZE_HUGE, - V4L2_CID_MPEG_VIDC_VIDEO_IFRAME_SIZE_UNLIMITED, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_CONCEAL_COLOR_8BIT \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 109) -#define V4L2_CID_MPEG_VIDC_VIDEO_CONCEAL_COLOR_10BIT \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 110) - -#define V4L2_CID_MPEG_VIDC_VIDEO_TME_PROFILE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 111) - -enum v4l2_mpeg_vidc_video_tme_profile { - V4L2_MPEG_VIDC_VIDEO_TME_PROFILE_0 = 0, - V4L2_MPEG_VIDC_VIDEO_TME_PROFILE_1 = 1, - V4L2_MPEG_VIDC_VIDEO_TME_PROFILE_2 = 2, - V4L2_MPEG_VIDC_VIDEO_TME_PROFILE_3 = 3, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_TME_LEVEL \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 112) - -enum v4l2_mpeg_vidc_video_tme_level { - V4L2_MPEG_VIDC_VIDEO_TME_LEVEL_INTEGER = 0, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_TME_PAYLOAD_VERSION \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 113) - -#define V4L2_CID_MPEG_VIDC_VIDEO_VPE_CSC_CUSTOM_MATRIX \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 114) - -#define V4L2_CID_MPEG_VIDC_VIDEO_FLIP (V4L2_CID_MPEG_MSM_VIDC_BASE + 115) -enum v4l2_mpeg_vidc_video_flip { - V4L2_CID_MPEG_VIDC_VIDEO_FLIP_NONE = 0, - V4L2_CID_MPEG_VIDC_VIDEO_FLIP_HORI = 1, - V4L2_CID_MPEG_VIDC_VIDEO_FLIP_VERT = 2, - V4L2_CID_MPEG_VIDC_VIDEO_FLIP_BOTH = 3, -}; - -/* HDR SEI INFO related control IDs and definitions*/ -#define V4L2_MPEG_VIDC_VENC_HDR_INFO_ENABLED 1 -#define V4L2_MPEG_VIDC_VENC_HDR_INFO_DISABLED 0 - -#define V4L2_CID_MPEG_VIDC_VENC_HDR_INFO \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 116) -#define V4L2_CID_MPEG_VIDC_VENC_RGB_PRIMARY_00 \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 117) -#define V4L2_CID_MPEG_VIDC_VENC_RGB_PRIMARY_01 \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 118) -#define V4L2_CID_MPEG_VIDC_VENC_RGB_PRIMARY_10 \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 119) -#define V4L2_CID_MPEG_VIDC_VENC_RGB_PRIMARY_11 \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 120) -#define V4L2_CID_MPEG_VIDC_VENC_RGB_PRIMARY_20 \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 121) -#define V4L2_CID_MPEG_VIDC_VENC_RGB_PRIMARY_21 \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 122) -#define V4L2_CID_MPEG_VIDC_VENC_WHITEPOINT_X \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 123) -#define V4L2_CID_MPEG_VIDC_VENC_WHITEPOINT_Y \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 124) -#define V4L2_CID_MPEG_VIDC_VENC_MAX_DISP_LUM \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 125) -#define V4L2_CID_MPEG_VIDC_VENC_MIN_DISP_LUM \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 126) -#define V4L2_CID_MPEG_VIDC_VENC_MAX_CLL \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 127) -#define V4L2_CID_MPEG_VIDC_VENC_MAX_FLL \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 128) - -#define V4L2_CID_MPEG_VIDC_SET_PERF_LEVEL \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 129) -enum v4l2_mpeg_vidc_perf_level { - V4L2_CID_MPEG_VIDC_PERF_LEVEL_NOMINAL = 0, - V4L2_CID_MPEG_VIDC_PERF_LEVEL_PERFORMANCE = 1, - V4L2_CID_MPEG_VIDC_PERF_LEVEL_TURBO = 2, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_AIR_MBS (V4L2_CID_MPEG_MSM_VIDC_BASE + 130) -#define V4L2_CID_MPEG_VIDC_VIDEO_AIR_REF (V4L2_CID_MPEG_MSM_VIDC_BASE + 131) -#define V4L2_CID_MPEG_VIDC_VIDEO_CIR_MBS (V4L2_CID_MPEG_MSM_VIDC_BASE + 132) - -#define V4L2_CID_MPEG_VIDC_VIDEO_H264_VUI_TIMING_INFO \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 135) - -#define V4L2_CID_MPEG_VIDEO_MULTI_SLICE_GOB \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 136) - -#define V4L2_CID_MPEG_VIDC_VIDEO_H264_VUI_BITSTREAM_RESTRICT \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 137) -enum v4l2_mpeg_vidc_video_h264_vui_bitstream_restrict { - V4L2_MPEG_VIDC_VIDEO_H264_VUI_BITSTREAM_RESTRICT_DISABLED = 0, - V4L2_MPEG_VIDC_VIDEO_H264_VUI_BITSTREAM_RESTRICT_ENABLED = 1 -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_DEINTERLACE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 138) -enum v4l2_mpeg_vidc_video_deinterlace { - V4L2_CID_MPEG_VIDC_VIDEO_DEINTERLACE_DISABLED = 0, - V4L2_CID_MPEG_VIDC_VIDEO_DEINTERLACE_ENABLED = 1 -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_MPEG4_TIME_RESOLUTION \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 139) - -#define V4L2_CID_MPEG_VIDC_VIDEO_REQUEST_SEQ_HEADER \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 140) - -#define V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_TIMESTAMP_MODE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 141) -enum v4l2_mpeg_vidc_video_rate_control_timestamp_mode { - V4L2_MPEG_VIDC_VIDEO_RATE_CONTROL_TIMESTAMP_MODE_HONOR = 0, - V4L2_MPEG_VIDC_VIDEO_RATE_CONTROL_TIMESTAMP_MODE_IGNORE = 1, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_ENABLE_INITIAL_QP \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 142) -enum vl42_mpeg_vidc_video_enable_initial_qp { - V4L2_CID_MPEG_VIDC_VIDEO_ENABLE_INITIAL_QP_IFRAME = 0x1, - V4L2_CID_MPEG_VIDC_VIDEO_ENABLE_INITIAL_QP_PFRAME = 0x2, - V4L2_CID_MPEG_VIDC_VIDEO_ENABLE_INITIAL_QP_BFRAME = 0x4, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_INITIAL_I_FRAME_QP \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 143) - -#define V4L2_CID_MPEG_VIDC_VIDEO_INITIAL_P_FRAME_QP \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 144) - -#define V4L2_CID_MPEG_VIDC_VIDEO_INITIAL_B_FRAME_QP \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 145) - -#define V4L2_CID_MPEG_VIDC_VIDEO_H264_NAL_SVC \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 146) - -#define V4L2_CID_MPEG_VIDC_VIDEO_PERF_MODE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 147) -enum v4l2_mpeg_vidc_video_perf_mode { - V4L2_MPEG_VIDC_VIDEO_PERF_MAX_QUALITY = 1, - V4L2_MPEG_VIDC_VIDEO_PERF_POWER_SAVE = 2 -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_MBI_STATISTICS_MODE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 148) - -#define V4L2_CID_MPEG_VIDC_VIDEO_CONFIG_QP \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 149) - -#define V4L2_CID_MPEG_VIDC_VIDEO_H264_PIC_ORDER_CNT \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 150) - -#define V4L2_CID_MPEG_VIDC_VIDEO_SCS_THRESHOLD \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 151) - -#define V4L2_CID_MPEG_VIDC_VIDEO_MVC_BUFFER_LAYOUT \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 152) - - -#define V4L2_CID_MPEG_VIDC_VIDEO_SECURE_SCALING_THRESHOLD \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 153) - -#define V4L2_CID_MPEG_VIDC_VIDEO_NON_SECURE_OUTPUT2 \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 154) - -#define V4L2_CID_MPEG_VIDC_VIDEO_VP8_MIN_QP (V4L2_CID_MPEG_MSM_VIDC_BASE + 155) -#define V4L2_CID_MPEG_VIDC_VIDEO_VP8_MAX_QP (V4L2_CID_MPEG_MSM_VIDC_BASE + 156) - -#define V4L2_CID_MPEG_VIDC_VIDEO_H263_LEVEL (V4L2_CID_MPEG_MSM_VIDC_BASE + 157) -enum v4l2_mpeg_vidc_video_h263_level { - V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_1_0 = 0, - V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_2_0 = 1, - V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_3_0 = 2, - V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_4_0 = 3, - V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_4_5 = 4, - V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_5_0 = 5, - V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_6_0 = 6, - V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_7_0 = 7, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_POST_LOOP_DEBLOCKER_MODE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 158) - - -#define V4L2_CID_MPEG_VIDC_VIDEO_DIVX_FORMAT (V4L2_CID_MPEG_MSM_VIDC_BASE+159) - -enum v4l2_mpeg_vidc_video_divx_format_type { - V4L2_MPEG_VIDC_VIDEO_DIVX_FORMAT_4 = 0, - V4L2_MPEG_VIDC_VIDEO_DIVX_FORMAT_5 = 1, - V4L2_MPEG_VIDC_VIDEO_DIVX_FORMAT_6 = 2, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_FRAME_QUALITY \ - (V4L2_CID_MPEG_MSM_VIDC_BASE+160) - -#define V4L2_CID_MPEG_VIDC_IMG_GRID_DIMENSION \ - (V4L2_CID_MPEG_MSM_VIDC_BASE+161) - -enum v4l2_mpeg_vidc_video_mbi_statistics_mode { - V4L2_CID_MPEG_VIDC_VIDEO_MBI_MODE_DEFAULT = 0, - V4L2_CID_MPEG_VIDC_VIDEO_MBI_MODE_1 = 1, - V4L2_CID_MPEG_VIDC_VIDEO_MBI_MODE_2 = 2, - V4L2_CID_MPEG_VIDC_VIDEO_MBI_MODE_3 = 3, -}; - -enum vl42_mpeg_vidc_video_h264_svc_nal { - V4L2_CID_MPEG_VIDC_VIDEO_H264_NAL_SVC_DISABLED = 0, - V4L2_CID_MPEG_VIDC_VIDEO_H264_NAL_SVC_ENABLED = 1, -}; - -enum v4l2_mpeg_vidc_video_h264_vui_timing_info { - V4L2_MPEG_VIDC_VIDEO_H264_VUI_TIMING_INFO_DISABLED = 0, - V4L2_MPEG_VIDC_VIDEO_H264_VUI_TIMING_INFO_ENABLED = 1 -}; - -/* Camera class control IDs */ - -#define V4L2_CID_CAMERA_CLASS_BASE (V4L2_CTRL_CLASS_CAMERA | 0x900) -#define V4L2_CID_CAMERA_CLASS (V4L2_CTRL_CLASS_CAMERA | 1) - -#define V4L2_CID_EXPOSURE_AUTO (V4L2_CID_CAMERA_CLASS_BASE+1) -enum v4l2_exposure_auto_type { - V4L2_EXPOSURE_AUTO = 0, - V4L2_EXPOSURE_MANUAL = 1, - V4L2_EXPOSURE_SHUTTER_PRIORITY = 2, - V4L2_EXPOSURE_APERTURE_PRIORITY = 3 -}; -#define V4L2_CID_EXPOSURE_ABSOLUTE (V4L2_CID_CAMERA_CLASS_BASE+2) -#define V4L2_CID_EXPOSURE_AUTO_PRIORITY (V4L2_CID_CAMERA_CLASS_BASE+3) - -#define V4L2_CID_PAN_RELATIVE (V4L2_CID_CAMERA_CLASS_BASE+4) -#define V4L2_CID_TILT_RELATIVE (V4L2_CID_CAMERA_CLASS_BASE+5) -#define V4L2_CID_PAN_RESET (V4L2_CID_CAMERA_CLASS_BASE+6) -#define V4L2_CID_TILT_RESET (V4L2_CID_CAMERA_CLASS_BASE+7) - -#define V4L2_CID_PAN_ABSOLUTE (V4L2_CID_CAMERA_CLASS_BASE+8) -#define V4L2_CID_TILT_ABSOLUTE (V4L2_CID_CAMERA_CLASS_BASE+9) - -#define V4L2_CID_FOCUS_ABSOLUTE (V4L2_CID_CAMERA_CLASS_BASE+10) -#define V4L2_CID_FOCUS_RELATIVE (V4L2_CID_CAMERA_CLASS_BASE+11) -#define V4L2_CID_FOCUS_AUTO (V4L2_CID_CAMERA_CLASS_BASE+12) - -#define V4L2_CID_ZOOM_ABSOLUTE (V4L2_CID_CAMERA_CLASS_BASE+13) -#define V4L2_CID_ZOOM_RELATIVE (V4L2_CID_CAMERA_CLASS_BASE+14) -#define V4L2_CID_ZOOM_CONTINUOUS (V4L2_CID_CAMERA_CLASS_BASE+15) - -#define V4L2_CID_PRIVACY (V4L2_CID_CAMERA_CLASS_BASE+16) - -#define V4L2_CID_IRIS_ABSOLUTE (V4L2_CID_CAMERA_CLASS_BASE+17) -#define V4L2_CID_IRIS_RELATIVE (V4L2_CID_CAMERA_CLASS_BASE+18) - -#define V4L2_CID_AUTO_EXPOSURE_BIAS (V4L2_CID_CAMERA_CLASS_BASE+19) - -#define V4L2_CID_AUTO_N_PRESET_WHITE_BALANCE (V4L2_CID_CAMERA_CLASS_BASE+20) -enum v4l2_auto_n_preset_white_balance { - V4L2_WHITE_BALANCE_MANUAL = 0, - V4L2_WHITE_BALANCE_AUTO = 1, - V4L2_WHITE_BALANCE_INCANDESCENT = 2, - V4L2_WHITE_BALANCE_FLUORESCENT = 3, - V4L2_WHITE_BALANCE_FLUORESCENT_H = 4, - V4L2_WHITE_BALANCE_HORIZON = 5, - V4L2_WHITE_BALANCE_DAYLIGHT = 6, - V4L2_WHITE_BALANCE_FLASH = 7, - V4L2_WHITE_BALANCE_CLOUDY = 8, - V4L2_WHITE_BALANCE_SHADE = 9, -}; - -#define V4L2_CID_WIDE_DYNAMIC_RANGE (V4L2_CID_CAMERA_CLASS_BASE+21) -#define V4L2_CID_IMAGE_STABILIZATION (V4L2_CID_CAMERA_CLASS_BASE+22) - -#define V4L2_CID_ISO_SENSITIVITY (V4L2_CID_CAMERA_CLASS_BASE+23) -#define V4L2_CID_ISO_SENSITIVITY_AUTO (V4L2_CID_CAMERA_CLASS_BASE+24) -enum v4l2_iso_sensitivity_auto_type { - V4L2_ISO_SENSITIVITY_MANUAL = 0, - V4L2_ISO_SENSITIVITY_AUTO = 1, -}; - -#define V4L2_CID_EXPOSURE_METERING (V4L2_CID_CAMERA_CLASS_BASE+25) -enum v4l2_exposure_metering { - V4L2_EXPOSURE_METERING_AVERAGE = 0, - V4L2_EXPOSURE_METERING_CENTER_WEIGHTED = 1, - V4L2_EXPOSURE_METERING_SPOT = 2, - V4L2_EXPOSURE_METERING_MATRIX = 3, -}; - -#define V4L2_CID_SCENE_MODE (V4L2_CID_CAMERA_CLASS_BASE+26) -enum v4l2_scene_mode { - V4L2_SCENE_MODE_NONE = 0, - V4L2_SCENE_MODE_BACKLIGHT = 1, - V4L2_SCENE_MODE_BEACH_SNOW = 2, - V4L2_SCENE_MODE_CANDLE_LIGHT = 3, - V4L2_SCENE_MODE_DAWN_DUSK = 4, - V4L2_SCENE_MODE_FALL_COLORS = 5, - V4L2_SCENE_MODE_FIREWORKS = 6, - V4L2_SCENE_MODE_LANDSCAPE = 7, - V4L2_SCENE_MODE_NIGHT = 8, - V4L2_SCENE_MODE_PARTY_INDOOR = 9, - V4L2_SCENE_MODE_PORTRAIT = 10, - V4L2_SCENE_MODE_SPORTS = 11, - V4L2_SCENE_MODE_SUNSET = 12, - V4L2_SCENE_MODE_TEXT = 13, -}; - -#define V4L2_CID_3A_LOCK (V4L2_CID_CAMERA_CLASS_BASE+27) -#define V4L2_LOCK_EXPOSURE (1 << 0) -#define V4L2_LOCK_WHITE_BALANCE (1 << 1) -#define V4L2_LOCK_FOCUS (1 << 2) - -#define V4L2_CID_AUTO_FOCUS_START (V4L2_CID_CAMERA_CLASS_BASE+28) -#define V4L2_CID_AUTO_FOCUS_STOP (V4L2_CID_CAMERA_CLASS_BASE+29) -#define V4L2_CID_AUTO_FOCUS_STATUS (V4L2_CID_CAMERA_CLASS_BASE+30) -#define V4L2_AUTO_FOCUS_STATUS_IDLE (0 << 0) -#define V4L2_AUTO_FOCUS_STATUS_BUSY (1 << 0) -#define V4L2_AUTO_FOCUS_STATUS_REACHED (1 << 1) -#define V4L2_AUTO_FOCUS_STATUS_FAILED (1 << 2) - -#define V4L2_CID_AUTO_FOCUS_RANGE (V4L2_CID_CAMERA_CLASS_BASE+31) -enum v4l2_auto_focus_range { - V4L2_AUTO_FOCUS_RANGE_AUTO = 0, - V4L2_AUTO_FOCUS_RANGE_NORMAL = 1, - V4L2_AUTO_FOCUS_RANGE_MACRO = 2, - V4L2_AUTO_FOCUS_RANGE_INFINITY = 3, -}; - -#define V4L2_CID_PAN_SPEED (V4L2_CID_CAMERA_CLASS_BASE+32) -#define V4L2_CID_TILT_SPEED (V4L2_CID_CAMERA_CLASS_BASE+33) - -/* FM Modulator class control IDs */ - -#define V4L2_CID_FM_TX_CLASS_BASE (V4L2_CTRL_CLASS_FM_TX | 0x900) -#define V4L2_CID_FM_TX_CLASS (V4L2_CTRL_CLASS_FM_TX | 1) - -#define V4L2_CID_RDS_TX_DEVIATION (V4L2_CID_FM_TX_CLASS_BASE + 1) -#define V4L2_CID_RDS_TX_PI (V4L2_CID_FM_TX_CLASS_BASE + 2) -#define V4L2_CID_RDS_TX_PTY (V4L2_CID_FM_TX_CLASS_BASE + 3) -#define V4L2_CID_RDS_TX_PS_NAME (V4L2_CID_FM_TX_CLASS_BASE + 5) -#define V4L2_CID_RDS_TX_RADIO_TEXT (V4L2_CID_FM_TX_CLASS_BASE + 6) -#define V4L2_CID_RDS_TX_MONO_STEREO (V4L2_CID_FM_TX_CLASS_BASE + 7) -#define V4L2_CID_RDS_TX_ARTIFICIAL_HEAD (V4L2_CID_FM_TX_CLASS_BASE + 8) -#define V4L2_CID_RDS_TX_COMPRESSED (V4L2_CID_FM_TX_CLASS_BASE + 9) -#define V4L2_CID_RDS_TX_DYNAMIC_PTY (V4L2_CID_FM_TX_CLASS_BASE + 10) -#define V4L2_CID_RDS_TX_TRAFFIC_ANNOUNCEMENT (V4L2_CID_FM_TX_CLASS_BASE + 11) -#define V4L2_CID_RDS_TX_TRAFFIC_PROGRAM (V4L2_CID_FM_TX_CLASS_BASE + 12) -#define V4L2_CID_RDS_TX_MUSIC_SPEECH (V4L2_CID_FM_TX_CLASS_BASE + 13) -#define V4L2_CID_RDS_TX_ALT_FREQS_ENABLE (V4L2_CID_FM_TX_CLASS_BASE + 14) -#define V4L2_CID_RDS_TX_ALT_FREQS (V4L2_CID_FM_TX_CLASS_BASE + 15) - -#define V4L2_CID_AUDIO_LIMITER_ENABLED (V4L2_CID_FM_TX_CLASS_BASE + 64) -#define V4L2_CID_AUDIO_LIMITER_RELEASE_TIME (V4L2_CID_FM_TX_CLASS_BASE + 65) -#define V4L2_CID_AUDIO_LIMITER_DEVIATION (V4L2_CID_FM_TX_CLASS_BASE + 66) - -#define V4L2_CID_AUDIO_COMPRESSION_ENABLED (V4L2_CID_FM_TX_CLASS_BASE + 80) -#define V4L2_CID_AUDIO_COMPRESSION_GAIN (V4L2_CID_FM_TX_CLASS_BASE + 81) -#define V4L2_CID_AUDIO_COMPRESSION_THRESHOLD (V4L2_CID_FM_TX_CLASS_BASE + 82) -#define V4L2_CID_AUDIO_COMPRESSION_ATTACK_TIME (V4L2_CID_FM_TX_CLASS_BASE + 83) -#define V4L2_CID_AUDIO_COMPRESSION_RELEASE_TIME (V4L2_CID_FM_TX_CLASS_BASE + 84) - -#define V4L2_CID_PILOT_TONE_ENABLED (V4L2_CID_FM_TX_CLASS_BASE + 96) -#define V4L2_CID_PILOT_TONE_DEVIATION (V4L2_CID_FM_TX_CLASS_BASE + 97) -#define V4L2_CID_PILOT_TONE_FREQUENCY (V4L2_CID_FM_TX_CLASS_BASE + 98) - -#define V4L2_CID_TUNE_PREEMPHASIS (V4L2_CID_FM_TX_CLASS_BASE + 112) -enum v4l2_preemphasis { - V4L2_PREEMPHASIS_DISABLED = 0, - V4L2_PREEMPHASIS_50_uS = 1, - V4L2_PREEMPHASIS_75_uS = 2, -}; -#define V4L2_CID_TUNE_POWER_LEVEL (V4L2_CID_FM_TX_CLASS_BASE + 113) -#define V4L2_CID_TUNE_ANTENNA_CAPACITOR (V4L2_CID_FM_TX_CLASS_BASE + 114) - - -/* Flash and privacy (indicator) light controls */ - -#define V4L2_CID_FLASH_CLASS_BASE (V4L2_CTRL_CLASS_FLASH | 0x900) -#define V4L2_CID_FLASH_CLASS (V4L2_CTRL_CLASS_FLASH | 1) - -#define V4L2_CID_FLASH_LED_MODE (V4L2_CID_FLASH_CLASS_BASE + 1) -enum v4l2_flash_led_mode { - V4L2_FLASH_LED_MODE_NONE, - V4L2_FLASH_LED_MODE_FLASH, - V4L2_FLASH_LED_MODE_TORCH, -}; - -#define V4L2_CID_FLASH_STROBE_SOURCE (V4L2_CID_FLASH_CLASS_BASE + 2) -enum v4l2_flash_strobe_source { - V4L2_FLASH_STROBE_SOURCE_SOFTWARE, - V4L2_FLASH_STROBE_SOURCE_EXTERNAL, -}; - -#define V4L2_CID_FLASH_STROBE (V4L2_CID_FLASH_CLASS_BASE + 3) -#define V4L2_CID_FLASH_STROBE_STOP (V4L2_CID_FLASH_CLASS_BASE + 4) -#define V4L2_CID_FLASH_STROBE_STATUS (V4L2_CID_FLASH_CLASS_BASE + 5) - -#define V4L2_CID_FLASH_TIMEOUT (V4L2_CID_FLASH_CLASS_BASE + 6) -#define V4L2_CID_FLASH_INTENSITY (V4L2_CID_FLASH_CLASS_BASE + 7) -#define V4L2_CID_FLASH_TORCH_INTENSITY (V4L2_CID_FLASH_CLASS_BASE + 8) -#define V4L2_CID_FLASH_INDICATOR_INTENSITY (V4L2_CID_FLASH_CLASS_BASE + 9) - -#define V4L2_CID_FLASH_FAULT (V4L2_CID_FLASH_CLASS_BASE + 10) -#define V4L2_FLASH_FAULT_OVER_VOLTAGE (1 << 0) -#define V4L2_FLASH_FAULT_TIMEOUT (1 << 1) -#define V4L2_FLASH_FAULT_OVER_TEMPERATURE (1 << 2) -#define V4L2_FLASH_FAULT_SHORT_CIRCUIT (1 << 3) -#define V4L2_FLASH_FAULT_OVER_CURRENT (1 << 4) -#define V4L2_FLASH_FAULT_INDICATOR (1 << 5) -#define V4L2_FLASH_FAULT_UNDER_VOLTAGE (1 << 6) -#define V4L2_FLASH_FAULT_INPUT_VOLTAGE (1 << 7) -#define V4L2_FLASH_FAULT_LED_OVER_TEMPERATURE (1 << 8) - -#define V4L2_CID_FLASH_CHARGE (V4L2_CID_FLASH_CLASS_BASE + 11) -#define V4L2_CID_FLASH_READY (V4L2_CID_FLASH_CLASS_BASE + 12) - - -/* JPEG-class control IDs */ - -#define V4L2_CID_JPEG_CLASS_BASE (V4L2_CTRL_CLASS_JPEG | 0x900) -#define V4L2_CID_JPEG_CLASS (V4L2_CTRL_CLASS_JPEG | 1) - -#define V4L2_CID_JPEG_CHROMA_SUBSAMPLING (V4L2_CID_JPEG_CLASS_BASE + 1) -enum v4l2_jpeg_chroma_subsampling { - V4L2_JPEG_CHROMA_SUBSAMPLING_444 = 0, - V4L2_JPEG_CHROMA_SUBSAMPLING_422 = 1, - V4L2_JPEG_CHROMA_SUBSAMPLING_420 = 2, - V4L2_JPEG_CHROMA_SUBSAMPLING_411 = 3, - V4L2_JPEG_CHROMA_SUBSAMPLING_410 = 4, - V4L2_JPEG_CHROMA_SUBSAMPLING_GRAY = 5, -}; -#define V4L2_CID_JPEG_RESTART_INTERVAL (V4L2_CID_JPEG_CLASS_BASE + 2) -#define V4L2_CID_JPEG_COMPRESSION_QUALITY (V4L2_CID_JPEG_CLASS_BASE + 3) - -#define V4L2_CID_JPEG_ACTIVE_MARKER (V4L2_CID_JPEG_CLASS_BASE + 4) -#define V4L2_JPEG_ACTIVE_MARKER_APP0 (1 << 0) -#define V4L2_JPEG_ACTIVE_MARKER_APP1 (1 << 1) -#define V4L2_JPEG_ACTIVE_MARKER_COM (1 << 16) -#define V4L2_JPEG_ACTIVE_MARKER_DQT (1 << 17) -#define V4L2_JPEG_ACTIVE_MARKER_DHT (1 << 18) - - -/* Image source controls */ -#define V4L2_CID_IMAGE_SOURCE_CLASS_BASE (V4L2_CTRL_CLASS_IMAGE_SOURCE | 0x900) -#define V4L2_CID_IMAGE_SOURCE_CLASS (V4L2_CTRL_CLASS_IMAGE_SOURCE | 1) - -#define V4L2_CID_VBLANK (V4L2_CID_IMAGE_SOURCE_CLASS_BASE + 1) -#define V4L2_CID_HBLANK (V4L2_CID_IMAGE_SOURCE_CLASS_BASE + 2) -#define V4L2_CID_ANALOGUE_GAIN (V4L2_CID_IMAGE_SOURCE_CLASS_BASE + 3) -#define V4L2_CID_TEST_PATTERN_RED (V4L2_CID_IMAGE_SOURCE_CLASS_BASE + 4) -#define V4L2_CID_TEST_PATTERN_GREENR (V4L2_CID_IMAGE_SOURCE_CLASS_BASE + 5) -#define V4L2_CID_TEST_PATTERN_BLUE (V4L2_CID_IMAGE_SOURCE_CLASS_BASE + 6) -#define V4L2_CID_TEST_PATTERN_GREENB (V4L2_CID_IMAGE_SOURCE_CLASS_BASE + 7) - - -/* Image processing controls */ - -#define V4L2_CID_IMAGE_PROC_CLASS_BASE (V4L2_CTRL_CLASS_IMAGE_PROC | 0x900) -#define V4L2_CID_IMAGE_PROC_CLASS (V4L2_CTRL_CLASS_IMAGE_PROC | 1) - -#define V4L2_CID_LINK_FREQ (V4L2_CID_IMAGE_PROC_CLASS_BASE + 1) -#define V4L2_CID_PIXEL_RATE (V4L2_CID_IMAGE_PROC_CLASS_BASE + 2) -#define V4L2_CID_TEST_PATTERN (V4L2_CID_IMAGE_PROC_CLASS_BASE + 3) - - -/* DV-class control IDs defined by V4L2 */ -#define V4L2_CID_DV_CLASS_BASE (V4L2_CTRL_CLASS_DV | 0x900) -#define V4L2_CID_DV_CLASS (V4L2_CTRL_CLASS_DV | 1) - -#define V4L2_CID_DV_TX_HOTPLUG (V4L2_CID_DV_CLASS_BASE + 1) -#define V4L2_CID_DV_TX_RXSENSE (V4L2_CID_DV_CLASS_BASE + 2) -#define V4L2_CID_DV_TX_EDID_PRESENT (V4L2_CID_DV_CLASS_BASE + 3) -#define V4L2_CID_DV_TX_MODE (V4L2_CID_DV_CLASS_BASE + 4) -enum v4l2_dv_tx_mode { - V4L2_DV_TX_MODE_DVI_D = 0, - V4L2_DV_TX_MODE_HDMI = 1, -}; -#define V4L2_CID_DV_TX_RGB_RANGE (V4L2_CID_DV_CLASS_BASE + 5) -enum v4l2_dv_rgb_range { - V4L2_DV_RGB_RANGE_AUTO = 0, - V4L2_DV_RGB_RANGE_LIMITED = 1, - V4L2_DV_RGB_RANGE_FULL = 2, -}; - -#define V4L2_CID_DV_TX_IT_CONTENT_TYPE (V4L2_CID_DV_CLASS_BASE + 6) -enum v4l2_dv_it_content_type { - V4L2_DV_IT_CONTENT_TYPE_GRAPHICS = 0, - V4L2_DV_IT_CONTENT_TYPE_PHOTO = 1, - V4L2_DV_IT_CONTENT_TYPE_CINEMA = 2, - V4L2_DV_IT_CONTENT_TYPE_GAME = 3, - V4L2_DV_IT_CONTENT_TYPE_NO_ITC = 4, -}; - -#define V4L2_CID_DV_RX_POWER_PRESENT (V4L2_CID_DV_CLASS_BASE + 100) -#define V4L2_CID_DV_RX_RGB_RANGE (V4L2_CID_DV_CLASS_BASE + 101) -#define V4L2_CID_DV_RX_IT_CONTENT_TYPE (V4L2_CID_DV_CLASS_BASE + 102) - -#define V4L2_CID_FM_RX_CLASS_BASE (V4L2_CTRL_CLASS_FM_RX | 0x900) -#define V4L2_CID_FM_RX_CLASS (V4L2_CTRL_CLASS_FM_RX | 1) - -#define V4L2_CID_TUNE_DEEMPHASIS (V4L2_CID_FM_RX_CLASS_BASE + 1) -enum v4l2_deemphasis { - V4L2_DEEMPHASIS_DISABLED = V4L2_PREEMPHASIS_DISABLED, - V4L2_DEEMPHASIS_50_uS = V4L2_PREEMPHASIS_50_uS, - V4L2_DEEMPHASIS_75_uS = V4L2_PREEMPHASIS_75_uS, -}; - -#define V4L2_CID_RDS_RECEPTION (V4L2_CID_FM_RX_CLASS_BASE + 2) -#define V4L2_CID_RDS_RX_PTY (V4L2_CID_FM_RX_CLASS_BASE + 3) -#define V4L2_CID_RDS_RX_PS_NAME (V4L2_CID_FM_RX_CLASS_BASE + 4) -#define V4L2_CID_RDS_RX_RADIO_TEXT (V4L2_CID_FM_RX_CLASS_BASE + 5) -#define V4L2_CID_RDS_RX_TRAFFIC_ANNOUNCEMENT (V4L2_CID_FM_RX_CLASS_BASE + 6) -#define V4L2_CID_RDS_RX_TRAFFIC_PROGRAM (V4L2_CID_FM_RX_CLASS_BASE + 7) -#define V4L2_CID_RDS_RX_MUSIC_SPEECH (V4L2_CID_FM_RX_CLASS_BASE + 8) - -#define V4L2_CID_RF_TUNER_CLASS_BASE (V4L2_CTRL_CLASS_RF_TUNER | 0x900) -#define V4L2_CID_RF_TUNER_CLASS (V4L2_CTRL_CLASS_RF_TUNER | 1) - -#define V4L2_CID_RF_TUNER_BANDWIDTH_AUTO (V4L2_CID_RF_TUNER_CLASS_BASE + 11) -#define V4L2_CID_RF_TUNER_BANDWIDTH (V4L2_CID_RF_TUNER_CLASS_BASE + 12) -#define V4L2_CID_RF_TUNER_RF_GAIN (V4L2_CID_RF_TUNER_CLASS_BASE + 32) -#define V4L2_CID_RF_TUNER_LNA_GAIN_AUTO (V4L2_CID_RF_TUNER_CLASS_BASE + 41) -#define V4L2_CID_RF_TUNER_LNA_GAIN (V4L2_CID_RF_TUNER_CLASS_BASE + 42) -#define V4L2_CID_RF_TUNER_MIXER_GAIN_AUTO (V4L2_CID_RF_TUNER_CLASS_BASE + 51) -#define V4L2_CID_RF_TUNER_MIXER_GAIN (V4L2_CID_RF_TUNER_CLASS_BASE + 52) -#define V4L2_CID_RF_TUNER_IF_GAIN_AUTO (V4L2_CID_RF_TUNER_CLASS_BASE + 61) -#define V4L2_CID_RF_TUNER_IF_GAIN (V4L2_CID_RF_TUNER_CLASS_BASE + 62) -#define V4L2_CID_RF_TUNER_PLL_LOCK (V4L2_CID_RF_TUNER_CLASS_BASE + 91) - - -/* Detection-class control IDs defined by V4L2 */ -#define V4L2_CID_DETECT_CLASS_BASE (V4L2_CTRL_CLASS_DETECT | 0x900) -#define V4L2_CID_DETECT_CLASS (V4L2_CTRL_CLASS_DETECT | 1) - -#define V4L2_CID_DETECT_MD_MODE (V4L2_CID_DETECT_CLASS_BASE + 1) -enum v4l2_detect_md_mode { - V4L2_DETECT_MD_MODE_DISABLED = 0, - V4L2_DETECT_MD_MODE_GLOBAL = 1, - V4L2_DETECT_MD_MODE_THRESHOLD_GRID = 2, - V4L2_DETECT_MD_MODE_REGION_GRID = 3, -}; -#define V4L2_CID_DETECT_MD_GLOBAL_THRESHOLD (V4L2_CID_DETECT_CLASS_BASE + 2) -#define V4L2_CID_DETECT_MD_THRESHOLD_GRID (V4L2_CID_DETECT_CLASS_BASE + 3) -#define V4L2_CID_DETECT_MD_REGION_GRID (V4L2_CID_DETECT_CLASS_BASE + 4) - -#endif diff --git a/third_party/raylib/.gitignore b/third_party/raylib/.gitignore deleted file mode 100644 index 6b1d3ad748..0000000000 --- a/third_party/raylib/.gitignore +++ /dev/null @@ -1,4 +0,0 @@ -/raylib_repo/ -/raylib_python_repo/ -/wheel/ -!*.a diff --git a/third_party/raylib/Darwin/libraylib.a b/third_party/raylib/Darwin/libraylib.a deleted file mode 100644 index dd2e9b33f1..0000000000 --- a/third_party/raylib/Darwin/libraylib.a +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:fd045c1d4bca5c9b2ad044ea730826ff6cedeef0b64451b123717b136f1cd702 -size 6392532 diff --git a/third_party/raylib/build.sh b/third_party/raylib/build.sh deleted file mode 100755 index d20f9d33af..0000000000 --- a/third_party/raylib/build.sh +++ /dev/null @@ -1,93 +0,0 @@ -#!/usr/bin/env bash -set -e - -export SOURCE_DATE_EPOCH=0 -export ZERO_AR_DATE=1 - -SUDO="" - -# Use sudo if not root -if [[ ! $(id -u) -eq 0 ]]; then - if [[ -z $(which sudo) ]]; then - echo "Please install sudo or run as root" - exit 1 - fi - SUDO="sudo" -fi - -DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )" -cd $DIR - -RAYLIB_PLATFORM="PLATFORM_DESKTOP" - -ARCHNAME=$(uname -m) -if [ -f /TICI ]; then - ARCHNAME="larch64" - RAYLIB_PLATFORM="PLATFORM_COMMA" -elif [[ "$OSTYPE" == "linux"* ]]; then - # required dependencies on Linux PC - $SUDO apt install \ - libxcursor-dev \ - libxi-dev \ - libxinerama-dev \ - libxrandr-dev -fi - -if [[ "$OSTYPE" == "darwin"* ]]; then - ARCHNAME="Darwin" -fi - -INSTALL_DIR="$DIR/$ARCHNAME" -rm -rf $INSTALL_DIR -mkdir -p $INSTALL_DIR - -INSTALL_H_DIR="$DIR/include" -rm -rf $INSTALL_H_DIR -mkdir -p $INSTALL_H_DIR - -if [ ! -d raylib_repo ]; then - git clone -b master --no-tags https://github.com/commaai/raylib.git raylib_repo -fi - -cd raylib_repo - -COMMIT=${1:-3425bd9d1fb292ede4d80f97a1f4f258f614cffc} -git fetch origin $COMMIT -git reset --hard $COMMIT -git clean -xdff . - -cd src - -make -j$(nproc) PLATFORM=$RAYLIB_PLATFORM RAYLIB_RELEASE_PATH=$INSTALL_DIR -cp raylib.h raymath.h rlgl.h $INSTALL_H_DIR/ -echo "raylib development files installed/updated in $INSTALL_H_DIR" - -# this commit needs to be in line with raylib -set -x -RAYGUI_COMMIT="76b36b597edb70ffaf96f046076adc20d67e7827" -curl -fsSLo $INSTALL_H_DIR/raygui.h https://raw.githubusercontent.com/raysan5/raygui/$RAYGUI_COMMIT/src/raygui.h - -if [ -f /TICI ]; then - - # Building the python bindings - cd $DIR - - if [ ! -d raylib_python_repo ]; then - git clone -b master --no-tags https://github.com/commaai/raylib-python-cffi.git raylib_python_repo - fi - - cd raylib_python_repo - - BINDINGS_COMMIT="a0710d95af3c12fd7f4b639589be9a13dad93cb6" - git fetch origin $BINDINGS_COMMIT - git reset --hard $BINDINGS_COMMIT - git clean -xdff . - - RAYLIB_PLATFORM=$RAYLIB_PLATFORM RAYLIB_INCLUDE_PATH=$INSTALL_H_DIR RAYLIB_LIB_PATH=$INSTALL_DIR python setup.py bdist_wheel - cd $DIR - - rm -rf wheel - mkdir wheel - cp raylib_python_repo/dist/*.whl wheel/ - -fi diff --git a/third_party/raylib/include/raygui.h b/third_party/raylib/include/raygui.h deleted file mode 100644 index fe233a16cf..0000000000 --- a/third_party/raylib/include/raygui.h +++ /dev/null @@ -1,5759 +0,0 @@ -/******************************************************************************************* -* -* raygui v4.5-dev - A simple and easy-to-use immediate-mode gui library -* -* DESCRIPTION: -* raygui is a tools-dev-focused immediate-mode-gui library based on raylib but also -* available as a standalone library, as long as input and drawing functions are provided. -* -* FEATURES: -* - Immediate-mode gui, minimal retained data -* - +25 controls provided (basic and advanced) -* - Styling system for colors, font and metrics -* - Icons supported, embedded as a 1-bit icons pack -* - Standalone mode option (custom input/graphics backend) -* - Multiple support tools provided for raygui development -* -* POSSIBLE IMPROVEMENTS: -* - Better standalone mode API for easy plug of custom backends -* - Externalize required inputs, allow user easier customization -* -* LIMITATIONS: -* - No editable multi-line word-wraped text box supported -* - No auto-layout mechanism, up to the user to define controls position and size -* - Standalone mode requires library modification and some user work to plug another backend -* -* NOTES: -* - WARNING: GuiLoadStyle() and GuiLoadStyle{Custom}() functions, allocate memory for -* font atlas recs and glyphs, freeing that memory is (usually) up to the user, -* no unload function is explicitly provided... but note that GuiLoadStyleDefault() unloads -* by default any previously loaded font (texture, recs, glyphs). -* - Global UI alpha (guiAlpha) is applied inside GuiDrawRectangle() and GuiDrawText() functions -* -* CONTROLS PROVIDED: -* # Container/separators Controls -* - WindowBox --> StatusBar, Panel -* - GroupBox --> Line -* - Line -* - Panel --> StatusBar -* - ScrollPanel --> StatusBar -* - TabBar --> Button -* -* # Basic Controls -* - Label -* - LabelButton --> Label -* - Button -* - Toggle -* - ToggleGroup --> Toggle -* - ToggleSlider -* - CheckBox -* - ComboBox -* - DropdownBox -* - TextBox -* - ValueBox --> TextBox -* - Spinner --> Button, ValueBox -* - Slider -* - SliderBar --> Slider -* - ProgressBar -* - StatusBar -* - DummyRec -* - Grid -* -* # Advance Controls -* - ListView -* - ColorPicker --> ColorPanel, ColorBarHue -* - MessageBox --> Window, Label, Button -* - TextInputBox --> Window, Label, TextBox, Button -* -* It also provides a set of functions for styling the controls based on its properties (size, color). -* -* -* RAYGUI STYLE (guiStyle): -* raygui uses a global data array for all gui style properties (allocated on data segment by default), -* when a new style is loaded, it is loaded over the global style... but a default gui style could always be -* recovered with GuiLoadStyleDefault() function, that overwrites the current style to the default one -* -* The global style array size is fixed and depends on the number of controls and properties: -* -* static unsigned int guiStyle[RAYGUI_MAX_CONTROLS*(RAYGUI_MAX_PROPS_BASE + RAYGUI_MAX_PROPS_EXTENDED)]; -* -* guiStyle size is by default: 16*(16 + 8) = 384*4 = 1536 bytes = 1.5 KB -* -* Note that the first set of BASE properties (by default guiStyle[0..15]) belong to the generic style -* used for all controls, when any of those base values is set, it is automatically populated to all -* controls, so, specific control values overwriting generic style should be set after base values. -* -* After the first BASE set we have the EXTENDED properties (by default guiStyle[16..23]), those -* properties are actually common to all controls and can not be overwritten individually (like BASE ones) -* Some of those properties are: TEXT_SIZE, TEXT_SPACING, LINE_COLOR, BACKGROUND_COLOR -* -* Custom control properties can be defined using the EXTENDED properties for each independent control. -* -* TOOL: rGuiStyler is a visual tool to customize raygui style: github.com/raysan5/rguistyler -* -* -* RAYGUI ICONS (guiIcons): -* raygui could use a global array containing icons data (allocated on data segment by default), -* a custom icons set could be loaded over this array using GuiLoadIcons(), but loaded icons set -* must be same RAYGUI_ICON_SIZE and no more than RAYGUI_ICON_MAX_ICONS will be loaded -* -* Every icon is codified in binary form, using 1 bit per pixel, so, every 16x16 icon -* requires 8 integers (16*16/32) to be stored in memory. -* -* When the icon is draw, actually one quad per pixel is drawn if the bit for that pixel is set. -* -* The global icons array size is fixed and depends on the number of icons and size: -* -* static unsigned int guiIcons[RAYGUI_ICON_MAX_ICONS*RAYGUI_ICON_DATA_ELEMENTS]; -* -* guiIcons size is by default: 256*(16*16/32) = 2048*4 = 8192 bytes = 8 KB -* -* TOOL: rGuiIcons is a visual tool to customize/create raygui icons: github.com/raysan5/rguiicons -* -* RAYGUI LAYOUT: -* raygui currently does not provide an auto-layout mechanism like other libraries, -* layouts must be defined manually on controls drawing, providing the right bounds Rectangle for it. -* -* TOOL: rGuiLayout is a visual tool to create raygui layouts: github.com/raysan5/rguilayout -* -* CONFIGURATION: -* #define RAYGUI_IMPLEMENTATION -* Generates the implementation of the library into the included file. -* If not defined, the library is in header only mode and can be included in other headers -* or source files without problems. But only ONE file should hold the implementation. -* -* #define RAYGUI_STANDALONE -* Avoid raylib.h header inclusion in this file. Data types defined on raylib are defined -* internally in the library and input management and drawing functions must be provided by -* the user (check library implementation for further details). -* -* #define RAYGUI_NO_ICONS -* Avoid including embedded ricons data (256 icons, 16x16 pixels, 1-bit per pixel, 2KB) -* -* #define RAYGUI_CUSTOM_ICONS -* Includes custom ricons.h header defining a set of custom icons, -* this file can be generated using rGuiIcons tool -* -* #define RAYGUI_DEBUG_RECS_BOUNDS -* Draw control bounds rectangles for debug -* -* #define RAYGUI_DEBUG_TEXT_BOUNDS -* Draw text bounds rectangles for debug -* -* VERSIONS HISTORY: -* 4.5-dev (Sep-2024) Current dev version... -* ADDED: guiControlExclusiveMode and guiControlExclusiveRec for exclusive modes -* ADDED: GuiValueBoxFloat() -* ADDED: GuiDropdonwBox() properties: DROPDOWN_ARROW_HIDDEN, DROPDOWN_ROLL_UP -* ADDED: GuiListView() property: LIST_ITEMS_BORDER_WIDTH -* ADDED: Multiple new icons -* REVIEWED: GuiTabBar(), close tab with mouse middle button -* REVIEWED: GuiScrollPanel(), scroll speed proportional to content -* REVIEWED: GuiDropdownBox(), support roll up and hidden arrow -* REVIEWED: GuiTextBox(), cursor position initialization -* REVIEWED: GuiSliderPro(), control value change check -* REVIEWED: GuiGrid(), simplified implementation -* REVIEWED: GuiIconText(), increase buffer size and reviewed padding -* REVIEWED: GuiDrawText(), improved wrap mode drawing -* REVIEWED: GuiScrollBar(), minor tweaks -* REVIEWED: Functions descriptions, removed wrong return value reference -* REDESIGNED: GuiColorPanel(), improved HSV <-> RGBA convertion -* -* 4.0 (12-Sep-2023) ADDED: GuiToggleSlider() -* ADDED: GuiColorPickerHSV() and GuiColorPanelHSV() -* ADDED: Multiple new icons, mostly compiler related -* ADDED: New DEFAULT properties: TEXT_LINE_SPACING, TEXT_ALIGNMENT_VERTICAL, TEXT_WRAP_MODE -* ADDED: New enum values: GuiTextAlignment, GuiTextAlignmentVertical, GuiTextWrapMode -* ADDED: Support loading styles with custom font charset from external file -* REDESIGNED: GuiTextBox(), support mouse cursor positioning -* REDESIGNED: GuiDrawText(), support multiline and word-wrap modes (read only) -* REDESIGNED: GuiProgressBar() to be more visual, progress affects border color -* REDESIGNED: Global alpha consideration moved to GuiDrawRectangle() and GuiDrawText() -* REDESIGNED: GuiScrollPanel(), get parameters by reference and return result value -* REDESIGNED: GuiToggleGroup(), get parameters by reference and return result value -* REDESIGNED: GuiComboBox(), get parameters by reference and return result value -* REDESIGNED: GuiCheckBox(), get parameters by reference and return result value -* REDESIGNED: GuiSlider(), get parameters by reference and return result value -* REDESIGNED: GuiSliderBar(), get parameters by reference and return result value -* REDESIGNED: GuiProgressBar(), get parameters by reference and return result value -* REDESIGNED: GuiListView(), get parameters by reference and return result value -* REDESIGNED: GuiColorPicker(), get parameters by reference and return result value -* REDESIGNED: GuiColorPanel(), get parameters by reference and return result value -* REDESIGNED: GuiColorBarAlpha(), get parameters by reference and return result value -* REDESIGNED: GuiColorBarHue(), get parameters by reference and return result value -* REDESIGNED: GuiGrid(), get parameters by reference and return result value -* REDESIGNED: GuiGrid(), added extra parameter -* REDESIGNED: GuiListViewEx(), change parameters order -* REDESIGNED: All controls return result as int value -* REVIEWED: GuiScrollPanel() to avoid smallish scroll-bars -* REVIEWED: All examples and specially controls_test_suite -* RENAMED: gui_file_dialog module to gui_window_file_dialog -* UPDATED: All styles to include ISO-8859-15 charset (as much as possible) -* -* 3.6 (10-May-2023) ADDED: New icon: SAND_TIMER -* ADDED: GuiLoadStyleFromMemory() (binary only) -* REVIEWED: GuiScrollBar() horizontal movement key -* REVIEWED: GuiTextBox() crash on cursor movement -* REVIEWED: GuiTextBox(), additional inputs support -* REVIEWED: GuiLabelButton(), avoid text cut -* REVIEWED: GuiTextInputBox(), password input -* REVIEWED: Local GetCodepointNext(), aligned with raylib -* REDESIGNED: GuiSlider*()/GuiScrollBar() to support out-of-bounds -* -* 3.5 (20-Apr-2023) ADDED: GuiTabBar(), based on GuiToggle() -* ADDED: Helper functions to split text in separate lines -* ADDED: Multiple new icons, useful for code editing tools -* REMOVED: Unneeded icon editing functions -* REMOVED: GuiTextBoxMulti(), very limited and broken -* REMOVED: MeasureTextEx() dependency, logic directly implemented -* REMOVED: DrawTextEx() dependency, logic directly implemented -* REVIEWED: GuiScrollBar(), improve mouse-click behaviour -* REVIEWED: Library header info, more info, better organized -* REDESIGNED: GuiTextBox() to support cursor movement -* REDESIGNED: GuiDrawText() to divide drawing by lines -* -* 3.2 (22-May-2022) RENAMED: Some enum values, for unification, avoiding prefixes -* REMOVED: GuiScrollBar(), only internal -* REDESIGNED: GuiPanel() to support text parameter -* REDESIGNED: GuiScrollPanel() to support text parameter -* REDESIGNED: GuiColorPicker() to support text parameter -* REDESIGNED: GuiColorPanel() to support text parameter -* REDESIGNED: GuiColorBarAlpha() to support text parameter -* REDESIGNED: GuiColorBarHue() to support text parameter -* REDESIGNED: GuiTextInputBox() to support password -* -* 3.1 (12-Jan-2022) REVIEWED: Default style for consistency (aligned with rGuiLayout v2.5 tool) -* REVIEWED: GuiLoadStyle() to support compressed font atlas image data and unload previous textures -* REVIEWED: External icons usage logic -* REVIEWED: GuiLine() for centered alignment when including text -* RENAMED: Multiple controls properties definitions to prepend RAYGUI_ -* RENAMED: RICON_ references to RAYGUI_ICON_ for library consistency -* Projects updated and multiple tweaks -* -* 3.0 (04-Nov-2021) Integrated ricons data to avoid external file -* REDESIGNED: GuiTextBoxMulti() -* REMOVED: GuiImageButton*() -* Multiple minor tweaks and bugs corrected -* -* 2.9 (17-Mar-2021) REMOVED: Tooltip API -* 2.8 (03-May-2020) Centralized rectangles drawing to GuiDrawRectangle() -* 2.7 (20-Feb-2020) ADDED: Possible tooltips API -* 2.6 (09-Sep-2019) ADDED: GuiTextInputBox() -* REDESIGNED: GuiListView*(), GuiDropdownBox(), GuiSlider*(), GuiProgressBar(), GuiMessageBox() -* REVIEWED: GuiTextBox(), GuiSpinner(), GuiValueBox(), GuiLoadStyle() -* Replaced property INNER_PADDING by TEXT_PADDING, renamed some properties -* ADDED: 8 new custom styles ready to use -* Multiple minor tweaks and bugs corrected -* -* 2.5 (28-May-2019) Implemented extended GuiTextBox(), GuiValueBox(), GuiSpinner() -* 2.3 (29-Apr-2019) ADDED: rIcons auxiliar library and support for it, multiple controls reviewed -* Refactor all controls drawing mechanism to use control state -* 2.2 (05-Feb-2019) ADDED: GuiScrollBar(), GuiScrollPanel(), reviewed GuiListView(), removed Gui*Ex() controls -* 2.1 (26-Dec-2018) REDESIGNED: GuiCheckBox(), GuiComboBox(), GuiDropdownBox(), GuiToggleGroup() > Use combined text string -* REDESIGNED: Style system (breaking change) -* 2.0 (08-Nov-2018) ADDED: Support controls guiLock and custom fonts -* REVIEWED: GuiComboBox(), GuiListView()... -* 1.9 (09-Oct-2018) REVIEWED: GuiGrid(), GuiTextBox(), GuiTextBoxMulti(), GuiValueBox()... -* 1.8 (01-May-2018) Lot of rework and redesign to align with rGuiStyler and rGuiLayout -* 1.5 (21-Jun-2017) Working in an improved styles system -* 1.4 (15-Jun-2017) Rewritten all GUI functions (removed useless ones) -* 1.3 (12-Jun-2017) Complete redesign of style system -* 1.1 (01-Jun-2017) Complete review of the library -* 1.0 (07-Jun-2016) Converted to header-only by Ramon Santamaria. -* 0.9 (07-Mar-2016) Reviewed and tested by Albert Martos, Ian Eito, Sergio Martinez and Ramon Santamaria. -* 0.8 (27-Aug-2015) Initial release. Implemented by Kevin Gato, Daniel Nicolás and Ramon Santamaria. -* -* DEPENDENCIES: -* raylib 5.0 - Inputs reading (keyboard/mouse), shapes drawing, font loading and text drawing -* -* STANDALONE MODE: -* By default raygui depends on raylib mostly for the inputs and the drawing functionality but that dependency can be disabled -* with the config flag RAYGUI_STANDALONE. In that case is up to the user to provide another backend to cover library needs. -* -* The following functions should be redefined for a custom backend: -* -* - Vector2 GetMousePosition(void); -* - float GetMouseWheelMove(void); -* - bool IsMouseButtonDown(int button); -* - bool IsMouseButtonPressed(int button); -* - bool IsMouseButtonReleased(int button); -* - bool IsKeyDown(int key); -* - bool IsKeyPressed(int key); -* - int GetCharPressed(void); // -- GuiTextBox(), GuiValueBox() -* -* - void DrawRectangle(int x, int y, int width, int height, Color color); // -- GuiDrawRectangle() -* - void DrawRectangleGradientEx(Rectangle rec, Color col1, Color col2, Color col3, Color col4); // -- GuiColorPicker() -* -* - Font GetFontDefault(void); // -- GuiLoadStyleDefault() -* - Font LoadFontEx(const char *fileName, int fontSize, int *codepoints, int codepointCount); // -- GuiLoadStyle() -* - Texture2D LoadTextureFromImage(Image image); // -- GuiLoadStyle(), required to load texture from embedded font atlas image -* - void SetShapesTexture(Texture2D tex, Rectangle rec); // -- GuiLoadStyle(), required to set shapes rec to font white rec (optimization) -* - char *LoadFileText(const char *fileName); // -- GuiLoadStyle(), required to load charset data -* - void UnloadFileText(char *text); // -- GuiLoadStyle(), required to unload charset data -* - const char *GetDirectoryPath(const char *filePath); // -- GuiLoadStyle(), required to find charset/font file from text .rgs -* - int *LoadCodepoints(const char *text, int *count); // -- GuiLoadStyle(), required to load required font codepoints list -* - void UnloadCodepoints(int *codepoints); // -- GuiLoadStyle(), required to unload codepoints list -* - unsigned char *DecompressData(const unsigned char *compData, int compDataSize, int *dataSize); // -- GuiLoadStyle() -* -* CONTRIBUTORS: -* Ramon Santamaria: Supervision, review, redesign, update and maintenance -* Vlad Adrian: Complete rewrite of GuiTextBox() to support extended features (2019) -* Sergio Martinez: Review, testing (2015) and redesign of multiple controls (2018) -* Adria Arranz: Testing and implementation of additional controls (2018) -* Jordi Jorba: Testing and implementation of additional controls (2018) -* Albert Martos: Review and testing of the library (2015) -* Ian Eito: Review and testing of the library (2015) -* Kevin Gato: Initial implementation of basic components (2014) -* Daniel Nicolas: Initial implementation of basic components (2014) -* -* -* LICENSE: zlib/libpng -* -* Copyright (c) 2014-2025 Ramon Santamaria (@raysan5) -* -* This software is provided "as-is", without any express or implied warranty. In no event -* will the authors be held liable for any damages arising from the use of this software. -* -* Permission is granted to anyone to use this software for any purpose, including commercial -* applications, and to alter it and redistribute it freely, subject to the following restrictions: -* -* 1. The origin of this software must not be misrepresented; you must not claim that you -* wrote the original software. If you use this software in a product, an acknowledgment -* in the product documentation would be appreciated but is not required. -* -* 2. Altered source versions must be plainly marked as such, and must not be misrepresented -* as being the original software. -* -* 3. This notice may not be removed or altered from any source distribution. -* -**********************************************************************************************/ - -#ifndef RAYGUI_H -#define RAYGUI_H - -#define RAYGUI_VERSION_MAJOR 4 -#define RAYGUI_VERSION_MINOR 5 -#define RAYGUI_VERSION_PATCH 0 -#define RAYGUI_VERSION "4.5-dev" - -#if !defined(RAYGUI_STANDALONE) - #include "raylib.h" -#endif - -// Function specifiers in case library is build/used as a shared library (Windows) -// NOTE: Microsoft specifiers to tell compiler that symbols are imported/exported from a .dll -#if defined(_WIN32) - #if defined(BUILD_LIBTYPE_SHARED) - #define RAYGUIAPI __declspec(dllexport) // We are building the library as a Win32 shared library (.dll) - #elif defined(USE_LIBTYPE_SHARED) - #define RAYGUIAPI __declspec(dllimport) // We are using the library as a Win32 shared library (.dll) - #endif -#endif - -// Function specifiers definition -#ifndef RAYGUIAPI - #define RAYGUIAPI // Functions defined as 'extern' by default (implicit specifiers) -#endif - -//---------------------------------------------------------------------------------- -// Defines and Macros -//---------------------------------------------------------------------------------- -// Allow custom memory allocators -#ifndef RAYGUI_MALLOC - #define RAYGUI_MALLOC(sz) malloc(sz) -#endif -#ifndef RAYGUI_CALLOC - #define RAYGUI_CALLOC(n,sz) calloc(n,sz) -#endif -#ifndef RAYGUI_FREE - #define RAYGUI_FREE(p) free(p) -#endif - -// Simple log system to avoid printf() calls if required -// NOTE: Avoiding those calls, also avoids const strings memory usage -#define RAYGUI_SUPPORT_LOG_INFO -#if defined(RAYGUI_SUPPORT_LOG_INFO) - #define RAYGUI_LOG(...) printf(__VA_ARGS__) -#else - #define RAYGUI_LOG(...) -#endif - -//---------------------------------------------------------------------------------- -// Types and Structures Definition -// NOTE: Some types are required for RAYGUI_STANDALONE usage -//---------------------------------------------------------------------------------- -#if defined(RAYGUI_STANDALONE) - #ifndef __cplusplus - // Boolean type - #ifndef true - typedef enum { false, true } bool; - #endif - #endif - - // Vector2 type - typedef struct Vector2 { - float x; - float y; - } Vector2; - - // Vector3 type // -- ConvertHSVtoRGB(), ConvertRGBtoHSV() - typedef struct Vector3 { - float x; - float y; - float z; - } Vector3; - - // Color type, RGBA (32bit) - typedef struct Color { - unsigned char r; - unsigned char g; - unsigned char b; - unsigned char a; - } Color; - - // Rectangle type - typedef struct Rectangle { - float x; - float y; - float width; - float height; - } Rectangle; - - // TODO: Texture2D type is very coupled to raylib, required by Font type - // It should be redesigned to be provided by user - typedef struct Texture2D { - unsigned int id; // OpenGL texture id - int width; // Texture base width - int height; // Texture base height - int mipmaps; // Mipmap levels, 1 by default - int format; // Data format (PixelFormat type) - } Texture2D; - - // Image, pixel data stored in CPU memory (RAM) - typedef struct Image { - void *data; // Image raw data - int width; // Image base width - int height; // Image base height - int mipmaps; // Mipmap levels, 1 by default - int format; // Data format (PixelFormat type) - } Image; - - // GlyphInfo, font characters glyphs info - typedef struct GlyphInfo { - int value; // Character value (Unicode) - int offsetX; // Character offset X when drawing - int offsetY; // Character offset Y when drawing - int advanceX; // Character advance position X - Image image; // Character image data - } GlyphInfo; - - // TODO: Font type is very coupled to raylib, mostly required by GuiLoadStyle() - // It should be redesigned to be provided by user - typedef struct Font { - int baseSize; // Base size (default chars height) - int glyphCount; // Number of glyph characters - int glyphPadding; // Padding around the glyph characters - Texture2D texture; // Texture atlas containing the glyphs - Rectangle *recs; // Rectangles in texture for the glyphs - GlyphInfo *glyphs; // Glyphs info data - } Font; -#endif - -// Style property -// NOTE: Used when exporting style as code for convenience -typedef struct GuiStyleProp { - unsigned short controlId; // Control identifier - unsigned short propertyId; // Property identifier - int propertyValue; // Property value -} GuiStyleProp; - -/* -// Controls text style -NOT USED- -// NOTE: Text style is defined by control -typedef struct GuiTextStyle { - unsigned int size; - int charSpacing; - int lineSpacing; - int alignmentH; - int alignmentV; - int padding; -} GuiTextStyle; -*/ - -// Gui control state -typedef enum { - STATE_NORMAL = 0, - STATE_FOCUSED, - STATE_PRESSED, - STATE_DISABLED -} GuiState; - -// Gui control text alignment -typedef enum { - TEXT_ALIGN_LEFT = 0, - TEXT_ALIGN_CENTER, - TEXT_ALIGN_RIGHT -} GuiTextAlignment; - -// Gui control text alignment vertical -// NOTE: Text vertical position inside the text bounds -typedef enum { - TEXT_ALIGN_TOP = 0, - TEXT_ALIGN_MIDDLE, - TEXT_ALIGN_BOTTOM -} GuiTextAlignmentVertical; - -// Gui control text wrap mode -// NOTE: Useful for multiline text -typedef enum { - TEXT_WRAP_NONE = 0, - TEXT_WRAP_CHAR, - TEXT_WRAP_WORD -} GuiTextWrapMode; - -// Gui controls -typedef enum { - // Default -> populates to all controls when set - DEFAULT = 0, - - // Basic controls - LABEL, // Used also for: LABELBUTTON - BUTTON, - TOGGLE, // Used also for: TOGGLEGROUP - SLIDER, // Used also for: SLIDERBAR, TOGGLESLIDER - PROGRESSBAR, - CHECKBOX, - COMBOBOX, - DROPDOWNBOX, - TEXTBOX, // Used also for: TEXTBOXMULTI - VALUEBOX, - SPINNER, // Uses: BUTTON, VALUEBOX - LISTVIEW, - COLORPICKER, - SCROLLBAR, - STATUSBAR -} GuiControl; - -// Gui base properties for every control -// NOTE: RAYGUI_MAX_PROPS_BASE properties (by default 16 properties) -typedef enum { - BORDER_COLOR_NORMAL = 0, // Control border color in STATE_NORMAL - BASE_COLOR_NORMAL, // Control base color in STATE_NORMAL - TEXT_COLOR_NORMAL, // Control text color in STATE_NORMAL - BORDER_COLOR_FOCUSED, // Control border color in STATE_FOCUSED - BASE_COLOR_FOCUSED, // Control base color in STATE_FOCUSED - TEXT_COLOR_FOCUSED, // Control text color in STATE_FOCUSED - BORDER_COLOR_PRESSED, // Control border color in STATE_PRESSED - BASE_COLOR_PRESSED, // Control base color in STATE_PRESSED - TEXT_COLOR_PRESSED, // Control text color in STATE_PRESSED - BORDER_COLOR_DISABLED, // Control border color in STATE_DISABLED - BASE_COLOR_DISABLED, // Control base color in STATE_DISABLED - TEXT_COLOR_DISABLED, // Control text color in STATE_DISABLED - BORDER_WIDTH, // Control border size, 0 for no border - //TEXT_SIZE, // Control text size (glyphs max height) -> GLOBAL for all controls - //TEXT_SPACING, // Control text spacing between glyphs -> GLOBAL for all controls - //TEXT_LINE_SPACING // Control text spacing between lines -> GLOBAL for all controls - TEXT_PADDING, // Control text padding, not considering border - TEXT_ALIGNMENT, // Control text horizontal alignment inside control text bound (after border and padding) - //TEXT_WRAP_MODE // Control text wrap-mode inside text bounds -> GLOBAL for all controls -} GuiControlProperty; - -// TODO: Which text styling properties should be global or per-control? -// At this moment TEXT_PADDING and TEXT_ALIGNMENT is configured and saved per control while -// TEXT_SIZE, TEXT_SPACING, TEXT_LINE_SPACING, TEXT_ALIGNMENT_VERTICAL, TEXT_WRAP_MODE are global and -// should be configured by user as needed while defining the UI layout - -// Gui extended properties depend on control -// NOTE: RAYGUI_MAX_PROPS_EXTENDED properties (by default, max 8 properties) -//---------------------------------------------------------------------------------- -// DEFAULT extended properties -// NOTE: Those properties are common to all controls or global -// WARNING: We only have 8 slots for those properties by default!!! -> New global control: TEXT? -typedef enum { - TEXT_SIZE = 16, // Text size (glyphs max height) - TEXT_SPACING, // Text spacing between glyphs - LINE_COLOR, // Line control color - BACKGROUND_COLOR, // Background color - TEXT_LINE_SPACING, // Text spacing between lines - TEXT_ALIGNMENT_VERTICAL, // Text vertical alignment inside text bounds (after border and padding) - TEXT_WRAP_MODE // Text wrap-mode inside text bounds - //TEXT_DECORATION // Text decoration: 0-None, 1-Underline, 2-Line-through, 3-Overline - //TEXT_DECORATION_THICK // Text decoration line thickness -} GuiDefaultProperty; - -// Other possible text properties: -// TEXT_WEIGHT // Normal, Italic, Bold -> Requires specific font change -// TEXT_INDENT // Text indentation -> Now using TEXT_PADDING... - -// Label -//typedef enum { } GuiLabelProperty; - -// Button/Spinner -//typedef enum { } GuiButtonProperty; - -// Toggle/ToggleGroup -typedef enum { - GROUP_PADDING = 16, // ToggleGroup separation between toggles -} GuiToggleProperty; - -// Slider/SliderBar -typedef enum { - SLIDER_WIDTH = 16, // Slider size of internal bar - SLIDER_PADDING // Slider/SliderBar internal bar padding -} GuiSliderProperty; - -// ProgressBar -typedef enum { - PROGRESS_PADDING = 16, // ProgressBar internal padding -} GuiProgressBarProperty; - -// ScrollBar -typedef enum { - ARROWS_SIZE = 16, // ScrollBar arrows size - ARROWS_VISIBLE, // ScrollBar arrows visible - SCROLL_SLIDER_PADDING, // ScrollBar slider internal padding - SCROLL_SLIDER_SIZE, // ScrollBar slider size - SCROLL_PADDING, // ScrollBar scroll padding from arrows - SCROLL_SPEED, // ScrollBar scrolling speed -} GuiScrollBarProperty; - -// CheckBox -typedef enum { - CHECK_PADDING = 16 // CheckBox internal check padding -} GuiCheckBoxProperty; - -// ComboBox -typedef enum { - COMBO_BUTTON_WIDTH = 16, // ComboBox right button width - COMBO_BUTTON_SPACING // ComboBox button separation -} GuiComboBoxProperty; - -// DropdownBox -typedef enum { - ARROW_PADDING = 16, // DropdownBox arrow separation from border and items - DROPDOWN_ITEMS_SPACING, // DropdownBox items separation - DROPDOWN_ARROW_HIDDEN, // DropdownBox arrow hidden - DROPDOWN_ROLL_UP // DropdownBox roll up flag (default rolls down) -} GuiDropdownBoxProperty; - -// TextBox/TextBoxMulti/ValueBox/Spinner -typedef enum { - TEXT_READONLY = 16, // TextBox in read-only mode: 0-text editable, 1-text no-editable -} GuiTextBoxProperty; - -// Spinner -typedef enum { - SPIN_BUTTON_WIDTH = 16, // Spinner left/right buttons width - SPIN_BUTTON_SPACING, // Spinner buttons separation -} GuiSpinnerProperty; - -// ListView -typedef enum { - LIST_ITEMS_HEIGHT = 16, // ListView items height - LIST_ITEMS_SPACING, // ListView items separation - SCROLLBAR_WIDTH, // ListView scrollbar size (usually width) - SCROLLBAR_SIDE, // ListView scrollbar side (0-SCROLLBAR_LEFT_SIDE, 1-SCROLLBAR_RIGHT_SIDE) - LIST_ITEMS_BORDER_WIDTH // ListView items border width -} GuiListViewProperty; - -// ColorPicker -typedef enum { - COLOR_SELECTOR_SIZE = 16, - HUEBAR_WIDTH, // ColorPicker right hue bar width - HUEBAR_PADDING, // ColorPicker right hue bar separation from panel - HUEBAR_SELECTOR_HEIGHT, // ColorPicker right hue bar selector height - HUEBAR_SELECTOR_OVERFLOW // ColorPicker right hue bar selector overflow -} GuiColorPickerProperty; - -#define SCROLLBAR_LEFT_SIDE 0 -#define SCROLLBAR_RIGHT_SIDE 1 - -//---------------------------------------------------------------------------------- -// Global Variables Definition -//---------------------------------------------------------------------------------- -// ... - -//---------------------------------------------------------------------------------- -// Module Functions Declaration -//---------------------------------------------------------------------------------- - -#if defined(__cplusplus) -extern "C" { // Prevents name mangling of functions -#endif - -// Global gui state control functions -RAYGUIAPI void GuiEnable(void); // Enable gui controls (global state) -RAYGUIAPI void GuiDisable(void); // Disable gui controls (global state) -RAYGUIAPI void GuiLock(void); // Lock gui controls (global state) -RAYGUIAPI void GuiUnlock(void); // Unlock gui controls (global state) -RAYGUIAPI bool GuiIsLocked(void); // Check if gui is locked (global state) -RAYGUIAPI void GuiSetAlpha(float alpha); // Set gui controls alpha (global state), alpha goes from 0.0f to 1.0f -RAYGUIAPI void GuiSetState(int state); // Set gui state (global state) -RAYGUIAPI int GuiGetState(void); // Get gui state (global state) - -// Font set/get functions -RAYGUIAPI void GuiSetFont(Font font); // Set gui custom font (global state) -RAYGUIAPI Font GuiGetFont(void); // Get gui custom font (global state) - -// Style set/get functions -RAYGUIAPI void GuiSetStyle(int control, int property, int value); // Set one style property -RAYGUIAPI int GuiGetStyle(int control, int property); // Get one style property - -// Styles loading functions -RAYGUIAPI void GuiLoadStyle(const char *fileName); // Load style file over global style variable (.rgs) -RAYGUIAPI void GuiLoadStyleDefault(void); // Load style default over global style - -// Tooltips management functions -RAYGUIAPI void GuiEnableTooltip(void); // Enable gui tooltips (global state) -RAYGUIAPI void GuiDisableTooltip(void); // Disable gui tooltips (global state) -RAYGUIAPI void GuiSetTooltip(const char *tooltip); // Set tooltip string - -// Icons functionality -RAYGUIAPI const char *GuiIconText(int iconId, const char *text); // Get text with icon id prepended (if supported) -#if !defined(RAYGUI_NO_ICONS) -RAYGUIAPI void GuiSetIconScale(int scale); // Set default icon drawing size -RAYGUIAPI unsigned int *GuiGetIcons(void); // Get raygui icons data pointer -RAYGUIAPI char **GuiLoadIcons(const char *fileName, bool loadIconsName); // Load raygui icons file (.rgi) into internal icons data -RAYGUIAPI void GuiDrawIcon(int iconId, int posX, int posY, int pixelSize, Color color); // Draw icon using pixel size at specified position -#endif - -// Controls -//---------------------------------------------------------------------------------------------------------- -// Container/separator controls, useful for controls organization -RAYGUIAPI int GuiWindowBox(Rectangle bounds, const char *title); // Window Box control, shows a window that can be closed -RAYGUIAPI int GuiGroupBox(Rectangle bounds, const char *text); // Group Box control with text name -RAYGUIAPI int GuiLine(Rectangle bounds, const char *text); // Line separator control, could contain text -RAYGUIAPI int GuiPanel(Rectangle bounds, const char *text); // Panel control, useful to group controls -RAYGUIAPI int GuiTabBar(Rectangle bounds, const char **text, int count, int *active); // Tab Bar control, returns TAB to be closed or -1 -RAYGUIAPI int GuiScrollPanel(Rectangle bounds, const char *text, Rectangle content, Vector2 *scroll, Rectangle *view); // Scroll Panel control - -// Basic controls set -RAYGUIAPI int GuiLabel(Rectangle bounds, const char *text); // Label control -RAYGUIAPI int GuiButton(Rectangle bounds, const char *text); // Button control, returns true when clicked -RAYGUIAPI int GuiLabelButton(Rectangle bounds, const char *text); // Label button control, returns true when clicked -RAYGUIAPI int GuiToggle(Rectangle bounds, const char *text, bool *active); // Toggle Button control -RAYGUIAPI int GuiToggleGroup(Rectangle bounds, const char *text, int *active); // Toggle Group control -RAYGUIAPI int GuiToggleSlider(Rectangle bounds, const char *text, int *active); // Toggle Slider control -RAYGUIAPI int GuiCheckBox(Rectangle bounds, const char *text, bool *checked); // Check Box control, returns true when active -RAYGUIAPI int GuiComboBox(Rectangle bounds, const char *text, int *active); // Combo Box control - -RAYGUIAPI int GuiDropdownBox(Rectangle bounds, const char *text, int *active, bool editMode); // Dropdown Box control -RAYGUIAPI int GuiSpinner(Rectangle bounds, const char *text, int *value, int minValue, int maxValue, bool editMode); // Spinner control -RAYGUIAPI int GuiValueBox(Rectangle bounds, const char *text, int *value, int minValue, int maxValue, bool editMode); // Value Box control, updates input text with numbers -RAYGUIAPI int GuiValueBoxFloat(Rectangle bounds, const char *text, char *textValue, float *value, bool editMode); // Value box control for float values -RAYGUIAPI int GuiTextBox(Rectangle bounds, char *text, int textSize, bool editMode); // Text Box control, updates input text - -RAYGUIAPI int GuiSlider(Rectangle bounds, const char *textLeft, const char *textRight, float *value, float minValue, float maxValue); // Slider control -RAYGUIAPI int GuiSliderBar(Rectangle bounds, const char *textLeft, const char *textRight, float *value, float minValue, float maxValue); // Slider Bar control -RAYGUIAPI int GuiProgressBar(Rectangle bounds, const char *textLeft, const char *textRight, float *value, float minValue, float maxValue); // Progress Bar control -RAYGUIAPI int GuiStatusBar(Rectangle bounds, const char *text); // Status Bar control, shows info text -RAYGUIAPI int GuiDummyRec(Rectangle bounds, const char *text); // Dummy control for placeholders -RAYGUIAPI int GuiGrid(Rectangle bounds, const char *text, float spacing, int subdivs, Vector2 *mouseCell); // Grid control - -// Advance controls set -RAYGUIAPI int GuiListView(Rectangle bounds, const char *text, int *scrollIndex, int *active); // List View control -RAYGUIAPI int GuiListViewEx(Rectangle bounds, const char **text, int count, int *scrollIndex, int *active, int *focus); // List View with extended parameters -RAYGUIAPI int GuiMessageBox(Rectangle bounds, const char *title, const char *message, const char *buttons); // Message Box control, displays a message -RAYGUIAPI int GuiTextInputBox(Rectangle bounds, const char *title, const char *message, const char *buttons, char *text, int textMaxSize, bool *secretViewActive); // Text Input Box control, ask for text, supports secret -RAYGUIAPI int GuiColorPicker(Rectangle bounds, const char *text, Color *color); // Color Picker control (multiple color controls) -RAYGUIAPI int GuiColorPanel(Rectangle bounds, const char *text, Color *color); // Color Panel control -RAYGUIAPI int GuiColorBarAlpha(Rectangle bounds, const char *text, float *alpha); // Color Bar Alpha control -RAYGUIAPI int GuiColorBarHue(Rectangle bounds, const char *text, float *value); // Color Bar Hue control -RAYGUIAPI int GuiColorPickerHSV(Rectangle bounds, const char *text, Vector3 *colorHsv); // Color Picker control that avoids conversion to RGB on each call (multiple color controls) -RAYGUIAPI int GuiColorPanelHSV(Rectangle bounds, const char *text, Vector3 *colorHsv); // Color Panel control that updates Hue-Saturation-Value color value, used by GuiColorPickerHSV() -//---------------------------------------------------------------------------------------------------------- - -#if !defined(RAYGUI_NO_ICONS) - -#if !defined(RAYGUI_CUSTOM_ICONS) -//---------------------------------------------------------------------------------- -// Icons enumeration -//---------------------------------------------------------------------------------- -typedef enum { - ICON_NONE = 0, - ICON_FOLDER_FILE_OPEN = 1, - ICON_FILE_SAVE_CLASSIC = 2, - ICON_FOLDER_OPEN = 3, - ICON_FOLDER_SAVE = 4, - ICON_FILE_OPEN = 5, - ICON_FILE_SAVE = 6, - ICON_FILE_EXPORT = 7, - ICON_FILE_ADD = 8, - ICON_FILE_DELETE = 9, - ICON_FILETYPE_TEXT = 10, - ICON_FILETYPE_AUDIO = 11, - ICON_FILETYPE_IMAGE = 12, - ICON_FILETYPE_PLAY = 13, - ICON_FILETYPE_VIDEO = 14, - ICON_FILETYPE_INFO = 15, - ICON_FILE_COPY = 16, - ICON_FILE_CUT = 17, - ICON_FILE_PASTE = 18, - ICON_CURSOR_HAND = 19, - ICON_CURSOR_POINTER = 20, - ICON_CURSOR_CLASSIC = 21, - ICON_PENCIL = 22, - ICON_PENCIL_BIG = 23, - ICON_BRUSH_CLASSIC = 24, - ICON_BRUSH_PAINTER = 25, - ICON_WATER_DROP = 26, - ICON_COLOR_PICKER = 27, - ICON_RUBBER = 28, - ICON_COLOR_BUCKET = 29, - ICON_TEXT_T = 30, - ICON_TEXT_A = 31, - ICON_SCALE = 32, - ICON_RESIZE = 33, - ICON_FILTER_POINT = 34, - ICON_FILTER_BILINEAR = 35, - ICON_CROP = 36, - ICON_CROP_ALPHA = 37, - ICON_SQUARE_TOGGLE = 38, - ICON_SYMMETRY = 39, - ICON_SYMMETRY_HORIZONTAL = 40, - ICON_SYMMETRY_VERTICAL = 41, - ICON_LENS = 42, - ICON_LENS_BIG = 43, - ICON_EYE_ON = 44, - ICON_EYE_OFF = 45, - ICON_FILTER_TOP = 46, - ICON_FILTER = 47, - ICON_TARGET_POINT = 48, - ICON_TARGET_SMALL = 49, - ICON_TARGET_BIG = 50, - ICON_TARGET_MOVE = 51, - ICON_CURSOR_MOVE = 52, - ICON_CURSOR_SCALE = 53, - ICON_CURSOR_SCALE_RIGHT = 54, - ICON_CURSOR_SCALE_LEFT = 55, - ICON_UNDO = 56, - ICON_REDO = 57, - ICON_REREDO = 58, - ICON_MUTATE = 59, - ICON_ROTATE = 60, - ICON_REPEAT = 61, - ICON_SHUFFLE = 62, - ICON_EMPTYBOX = 63, - ICON_TARGET = 64, - ICON_TARGET_SMALL_FILL = 65, - ICON_TARGET_BIG_FILL = 66, - ICON_TARGET_MOVE_FILL = 67, - ICON_CURSOR_MOVE_FILL = 68, - ICON_CURSOR_SCALE_FILL = 69, - ICON_CURSOR_SCALE_RIGHT_FILL = 70, - ICON_CURSOR_SCALE_LEFT_FILL = 71, - ICON_UNDO_FILL = 72, - ICON_REDO_FILL = 73, - ICON_REREDO_FILL = 74, - ICON_MUTATE_FILL = 75, - ICON_ROTATE_FILL = 76, - ICON_REPEAT_FILL = 77, - ICON_SHUFFLE_FILL = 78, - ICON_EMPTYBOX_SMALL = 79, - ICON_BOX = 80, - ICON_BOX_TOP = 81, - ICON_BOX_TOP_RIGHT = 82, - ICON_BOX_RIGHT = 83, - ICON_BOX_BOTTOM_RIGHT = 84, - ICON_BOX_BOTTOM = 85, - ICON_BOX_BOTTOM_LEFT = 86, - ICON_BOX_LEFT = 87, - ICON_BOX_TOP_LEFT = 88, - ICON_BOX_CENTER = 89, - ICON_BOX_CIRCLE_MASK = 90, - ICON_POT = 91, - ICON_ALPHA_MULTIPLY = 92, - ICON_ALPHA_CLEAR = 93, - ICON_DITHERING = 94, - ICON_MIPMAPS = 95, - ICON_BOX_GRID = 96, - ICON_GRID = 97, - ICON_BOX_CORNERS_SMALL = 98, - ICON_BOX_CORNERS_BIG = 99, - ICON_FOUR_BOXES = 100, - ICON_GRID_FILL = 101, - ICON_BOX_MULTISIZE = 102, - ICON_ZOOM_SMALL = 103, - ICON_ZOOM_MEDIUM = 104, - ICON_ZOOM_BIG = 105, - ICON_ZOOM_ALL = 106, - ICON_ZOOM_CENTER = 107, - ICON_BOX_DOTS_SMALL = 108, - ICON_BOX_DOTS_BIG = 109, - ICON_BOX_CONCENTRIC = 110, - ICON_BOX_GRID_BIG = 111, - ICON_OK_TICK = 112, - ICON_CROSS = 113, - ICON_ARROW_LEFT = 114, - ICON_ARROW_RIGHT = 115, - ICON_ARROW_DOWN = 116, - ICON_ARROW_UP = 117, - ICON_ARROW_LEFT_FILL = 118, - ICON_ARROW_RIGHT_FILL = 119, - ICON_ARROW_DOWN_FILL = 120, - ICON_ARROW_UP_FILL = 121, - ICON_AUDIO = 122, - ICON_FX = 123, - ICON_WAVE = 124, - ICON_WAVE_SINUS = 125, - ICON_WAVE_SQUARE = 126, - ICON_WAVE_TRIANGULAR = 127, - ICON_CROSS_SMALL = 128, - ICON_PLAYER_PREVIOUS = 129, - ICON_PLAYER_PLAY_BACK = 130, - ICON_PLAYER_PLAY = 131, - ICON_PLAYER_PAUSE = 132, - ICON_PLAYER_STOP = 133, - ICON_PLAYER_NEXT = 134, - ICON_PLAYER_RECORD = 135, - ICON_MAGNET = 136, - ICON_LOCK_CLOSE = 137, - ICON_LOCK_OPEN = 138, - ICON_CLOCK = 139, - ICON_TOOLS = 140, - ICON_GEAR = 141, - ICON_GEAR_BIG = 142, - ICON_BIN = 143, - ICON_HAND_POINTER = 144, - ICON_LASER = 145, - ICON_COIN = 146, - ICON_EXPLOSION = 147, - ICON_1UP = 148, - ICON_PLAYER = 149, - ICON_PLAYER_JUMP = 150, - ICON_KEY = 151, - ICON_DEMON = 152, - ICON_TEXT_POPUP = 153, - ICON_GEAR_EX = 154, - ICON_CRACK = 155, - ICON_CRACK_POINTS = 156, - ICON_STAR = 157, - ICON_DOOR = 158, - ICON_EXIT = 159, - ICON_MODE_2D = 160, - ICON_MODE_3D = 161, - ICON_CUBE = 162, - ICON_CUBE_FACE_TOP = 163, - ICON_CUBE_FACE_LEFT = 164, - ICON_CUBE_FACE_FRONT = 165, - ICON_CUBE_FACE_BOTTOM = 166, - ICON_CUBE_FACE_RIGHT = 167, - ICON_CUBE_FACE_BACK = 168, - ICON_CAMERA = 169, - ICON_SPECIAL = 170, - ICON_LINK_NET = 171, - ICON_LINK_BOXES = 172, - ICON_LINK_MULTI = 173, - ICON_LINK = 174, - ICON_LINK_BROKE = 175, - ICON_TEXT_NOTES = 176, - ICON_NOTEBOOK = 177, - ICON_SUITCASE = 178, - ICON_SUITCASE_ZIP = 179, - ICON_MAILBOX = 180, - ICON_MONITOR = 181, - ICON_PRINTER = 182, - ICON_PHOTO_CAMERA = 183, - ICON_PHOTO_CAMERA_FLASH = 184, - ICON_HOUSE = 185, - ICON_HEART = 186, - ICON_CORNER = 187, - ICON_VERTICAL_BARS = 188, - ICON_VERTICAL_BARS_FILL = 189, - ICON_LIFE_BARS = 190, - ICON_INFO = 191, - ICON_CROSSLINE = 192, - ICON_HELP = 193, - ICON_FILETYPE_ALPHA = 194, - ICON_FILETYPE_HOME = 195, - ICON_LAYERS_VISIBLE = 196, - ICON_LAYERS = 197, - ICON_WINDOW = 198, - ICON_HIDPI = 199, - ICON_FILETYPE_BINARY = 200, - ICON_HEX = 201, - ICON_SHIELD = 202, - ICON_FILE_NEW = 203, - ICON_FOLDER_ADD = 204, - ICON_ALARM = 205, - ICON_CPU = 206, - ICON_ROM = 207, - ICON_STEP_OVER = 208, - ICON_STEP_INTO = 209, - ICON_STEP_OUT = 210, - ICON_RESTART = 211, - ICON_BREAKPOINT_ON = 212, - ICON_BREAKPOINT_OFF = 213, - ICON_BURGER_MENU = 214, - ICON_CASE_SENSITIVE = 215, - ICON_REG_EXP = 216, - ICON_FOLDER = 217, - ICON_FILE = 218, - ICON_SAND_TIMER = 219, - ICON_WARNING = 220, - ICON_HELP_BOX = 221, - ICON_INFO_BOX = 222, - ICON_PRIORITY = 223, - ICON_LAYERS_ISO = 224, - ICON_LAYERS2 = 225, - ICON_MLAYERS = 226, - ICON_MAPS = 227, - ICON_HOT = 228, - ICON_229 = 229, - ICON_230 = 230, - ICON_231 = 231, - ICON_232 = 232, - ICON_233 = 233, - ICON_234 = 234, - ICON_235 = 235, - ICON_236 = 236, - ICON_237 = 237, - ICON_238 = 238, - ICON_239 = 239, - ICON_240 = 240, - ICON_241 = 241, - ICON_242 = 242, - ICON_243 = 243, - ICON_244 = 244, - ICON_245 = 245, - ICON_246 = 246, - ICON_247 = 247, - ICON_248 = 248, - ICON_249 = 249, - ICON_250 = 250, - ICON_251 = 251, - ICON_252 = 252, - ICON_253 = 253, - ICON_254 = 254, - ICON_255 = 255, -} GuiIconName; -#endif - -#endif - -#if defined(__cplusplus) -} // Prevents name mangling of functions -#endif - -#endif // RAYGUI_H - -/*********************************************************************************** -* -* RAYGUI IMPLEMENTATION -* -************************************************************************************/ - -#if defined(RAYGUI_IMPLEMENTATION) - -#include // required for: isspace() [GuiTextBox()] -#include // Required for: FILE, fopen(), fclose(), fprintf(), feof(), fscanf(), vsprintf() [GuiLoadStyle(), GuiLoadIcons()] -#include // Required for: malloc(), calloc(), free() [GuiLoadStyle(), GuiLoadIcons()] -#include // Required for: strlen() [GuiTextBox(), GuiValueBox()], memset(), memcpy() -#include // Required for: va_list, va_start(), vfprintf(), va_end() [TextFormat()] -#include // Required for: roundf() [GuiColorPicker()] - -#ifdef __cplusplus - #define RAYGUI_CLITERAL(name) name -#else - #define RAYGUI_CLITERAL(name) (name) -#endif - -// Check if two rectangles are equal, used to validate a slider bounds as an id -#ifndef CHECK_BOUNDS_ID - #define CHECK_BOUNDS_ID(src, dst) ((src.x == dst.x) && (src.y == dst.y) && (src.width == dst.width) && (src.height == dst.height)) -#endif - -#if !defined(RAYGUI_NO_ICONS) && !defined(RAYGUI_CUSTOM_ICONS) - -// Embedded icons, no external file provided -#define RAYGUI_ICON_SIZE 16 // Size of icons in pixels (squared) -#define RAYGUI_ICON_MAX_ICONS 256 // Maximum number of icons -#define RAYGUI_ICON_MAX_NAME_LENGTH 32 // Maximum length of icon name id - -// Icons data is defined by bit array (every bit represents one pixel) -// Those arrays are stored as unsigned int data arrays, so, -// every array element defines 32 pixels (bits) of information -// One icon is defined by 8 int, (8 int * 32 bit = 256 bit = 16*16 pixels) -// NOTE: Number of elemens depend on RAYGUI_ICON_SIZE (by default 16x16 pixels) -#define RAYGUI_ICON_DATA_ELEMENTS (RAYGUI_ICON_SIZE*RAYGUI_ICON_SIZE/32) - -//---------------------------------------------------------------------------------- -// Icons data for all gui possible icons (allocated on data segment by default) -// -// NOTE 1: Every icon is codified in binary form, using 1 bit per pixel, so, -// every 16x16 icon requires 8 integers (16*16/32) to be stored -// -// NOTE 2: A different icon set could be loaded over this array using GuiLoadIcons(), -// but loaded icons set must be same RAYGUI_ICON_SIZE and no more than RAYGUI_ICON_MAX_ICONS -// -// guiIcons size is by default: 256*(16*16/32) = 2048*4 = 8192 bytes = 8 KB -//---------------------------------------------------------------------------------- -static unsigned int guiIcons[RAYGUI_ICON_MAX_ICONS*RAYGUI_ICON_DATA_ELEMENTS] = { - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, // ICON_NONE - 0x3ff80000, 0x2f082008, 0x2042207e, 0x40027fc2, 0x40024002, 0x40024002, 0x40024002, 0x00007ffe, // ICON_FOLDER_FILE_OPEN - 0x3ffe0000, 0x44226422, 0x400247e2, 0x5ffa4002, 0x57ea500a, 0x500a500a, 0x40025ffa, 0x00007ffe, // ICON_FILE_SAVE_CLASSIC - 0x00000000, 0x0042007e, 0x40027fc2, 0x40024002, 0x41024002, 0x44424282, 0x793e4102, 0x00000100, // ICON_FOLDER_OPEN - 0x00000000, 0x0042007e, 0x40027fc2, 0x40024002, 0x41024102, 0x44424102, 0x793e4282, 0x00000000, // ICON_FOLDER_SAVE - 0x3ff00000, 0x201c2010, 0x20042004, 0x21042004, 0x24442284, 0x21042104, 0x20042104, 0x00003ffc, // ICON_FILE_OPEN - 0x3ff00000, 0x201c2010, 0x20042004, 0x21042004, 0x21042104, 0x22842444, 0x20042104, 0x00003ffc, // ICON_FILE_SAVE - 0x3ff00000, 0x201c2010, 0x00042004, 0x20041004, 0x20844784, 0x00841384, 0x20042784, 0x00003ffc, // ICON_FILE_EXPORT - 0x3ff00000, 0x201c2010, 0x20042004, 0x20042004, 0x22042204, 0x22042f84, 0x20042204, 0x00003ffc, // ICON_FILE_ADD - 0x3ff00000, 0x201c2010, 0x20042004, 0x20042004, 0x25042884, 0x25042204, 0x20042884, 0x00003ffc, // ICON_FILE_DELETE - 0x3ff00000, 0x201c2010, 0x20042004, 0x20042ff4, 0x20042ff4, 0x20042ff4, 0x20042004, 0x00003ffc, // ICON_FILETYPE_TEXT - 0x3ff00000, 0x201c2010, 0x27042004, 0x244424c4, 0x26442444, 0x20642664, 0x20042004, 0x00003ffc, // ICON_FILETYPE_AUDIO - 0x3ff00000, 0x201c2010, 0x26042604, 0x20042004, 0x35442884, 0x2414222c, 0x20042004, 0x00003ffc, // ICON_FILETYPE_IMAGE - 0x3ff00000, 0x201c2010, 0x20c42004, 0x22442144, 0x22442444, 0x20c42144, 0x20042004, 0x00003ffc, // ICON_FILETYPE_PLAY - 0x3ff00000, 0x3ffc2ff0, 0x3f3c2ff4, 0x3dbc2eb4, 0x3dbc2bb4, 0x3f3c2eb4, 0x3ffc2ff4, 0x00002ff4, // ICON_FILETYPE_VIDEO - 0x3ff00000, 0x201c2010, 0x21842184, 0x21842004, 0x21842184, 0x21842184, 0x20042184, 0x00003ffc, // ICON_FILETYPE_INFO - 0x0ff00000, 0x381c0810, 0x28042804, 0x28042804, 0x28042804, 0x28042804, 0x20102ffc, 0x00003ff0, // ICON_FILE_COPY - 0x00000000, 0x701c0000, 0x079c1e14, 0x55a000f0, 0x079c00f0, 0x701c1e14, 0x00000000, 0x00000000, // ICON_FILE_CUT - 0x01c00000, 0x13e41bec, 0x3f841004, 0x204420c4, 0x20442044, 0x20442044, 0x207c2044, 0x00003fc0, // ICON_FILE_PASTE - 0x00000000, 0x3aa00fe0, 0x2abc2aa0, 0x2aa42aa4, 0x20042aa4, 0x20042004, 0x3ffc2004, 0x00000000, // ICON_CURSOR_HAND - 0x00000000, 0x003c000c, 0x030800c8, 0x30100c10, 0x10202020, 0x04400840, 0x01800280, 0x00000000, // ICON_CURSOR_POINTER - 0x00000000, 0x00180000, 0x01f00078, 0x03e007f0, 0x07c003e0, 0x04000e40, 0x00000000, 0x00000000, // ICON_CURSOR_CLASSIC - 0x00000000, 0x04000000, 0x11000a00, 0x04400a80, 0x01100220, 0x00580088, 0x00000038, 0x00000000, // ICON_PENCIL - 0x04000000, 0x15000a00, 0x50402880, 0x14102820, 0x05040a08, 0x015c028c, 0x007c00bc, 0x00000000, // ICON_PENCIL_BIG - 0x01c00000, 0x01400140, 0x01400140, 0x0ff80140, 0x0ff80808, 0x0aa80808, 0x0aa80aa8, 0x00000ff8, // ICON_BRUSH_CLASSIC - 0x1ffc0000, 0x5ffc7ffe, 0x40004000, 0x00807f80, 0x01c001c0, 0x01c001c0, 0x01c001c0, 0x00000080, // ICON_BRUSH_PAINTER - 0x00000000, 0x00800000, 0x01c00080, 0x03e001c0, 0x07f003e0, 0x036006f0, 0x000001c0, 0x00000000, // ICON_WATER_DROP - 0x00000000, 0x3e003800, 0x1f803f80, 0x0c201e40, 0x02080c10, 0x00840104, 0x00380044, 0x00000000, // ICON_COLOR_PICKER - 0x00000000, 0x07800300, 0x1fe00fc0, 0x3f883fd0, 0x0e021f04, 0x02040402, 0x00f00108, 0x00000000, // ICON_RUBBER - 0x00c00000, 0x02800140, 0x08200440, 0x20081010, 0x2ffe3004, 0x03f807fc, 0x00e001f0, 0x00000040, // ICON_COLOR_BUCKET - 0x00000000, 0x21843ffc, 0x01800180, 0x01800180, 0x01800180, 0x01800180, 0x03c00180, 0x00000000, // ICON_TEXT_T - 0x00800000, 0x01400180, 0x06200340, 0x0c100620, 0x1ff80c10, 0x380c1808, 0x70067004, 0x0000f80f, // ICON_TEXT_A - 0x78000000, 0x50004000, 0x00004800, 0x03c003c0, 0x03c003c0, 0x00100000, 0x0002000a, 0x0000000e, // ICON_SCALE - 0x75560000, 0x5e004002, 0x54001002, 0x41001202, 0x408200fe, 0x40820082, 0x40820082, 0x00006afe, // ICON_RESIZE - 0x00000000, 0x3f003f00, 0x3f003f00, 0x3f003f00, 0x00400080, 0x001c0020, 0x001c001c, 0x00000000, // ICON_FILTER_POINT - 0x6d800000, 0x00004080, 0x40804080, 0x40800000, 0x00406d80, 0x001c0020, 0x001c001c, 0x00000000, // ICON_FILTER_BILINEAR - 0x40080000, 0x1ffe2008, 0x14081008, 0x11081208, 0x10481088, 0x10081028, 0x10047ff8, 0x00001002, // ICON_CROP - 0x00100000, 0x3ffc0010, 0x2ab03550, 0x22b02550, 0x20b02150, 0x20302050, 0x2000fff0, 0x00002000, // ICON_CROP_ALPHA - 0x40000000, 0x1ff82000, 0x04082808, 0x01082208, 0x00482088, 0x00182028, 0x35542008, 0x00000002, // ICON_SQUARE_TOGGLE - 0x00000000, 0x02800280, 0x06c006c0, 0x0ea00ee0, 0x1e901eb0, 0x3e883e98, 0x7efc7e8c, 0x00000000, // ICON_SYMMETRY - 0x01000000, 0x05600100, 0x1d480d50, 0x7d423d44, 0x3d447d42, 0x0d501d48, 0x01000560, 0x00000100, // ICON_SYMMETRY_HORIZONTAL - 0x01800000, 0x04200240, 0x10080810, 0x00001ff8, 0x00007ffe, 0x0ff01ff8, 0x03c007e0, 0x00000180, // ICON_SYMMETRY_VERTICAL - 0x00000000, 0x010800f0, 0x02040204, 0x02040204, 0x07f00308, 0x1c000e00, 0x30003800, 0x00000000, // ICON_LENS - 0x00000000, 0x061803f0, 0x08240c0c, 0x08040814, 0x0c0c0804, 0x23f01618, 0x18002400, 0x00000000, // ICON_LENS_BIG - 0x00000000, 0x00000000, 0x1c7007c0, 0x638e3398, 0x1c703398, 0x000007c0, 0x00000000, 0x00000000, // ICON_EYE_ON - 0x00000000, 0x10002000, 0x04700fc0, 0x610e3218, 0x1c703098, 0x001007a0, 0x00000008, 0x00000000, // ICON_EYE_OFF - 0x00000000, 0x00007ffc, 0x40047ffc, 0x10102008, 0x04400820, 0x02800280, 0x02800280, 0x00000100, // ICON_FILTER_TOP - 0x00000000, 0x40027ffe, 0x10082004, 0x04200810, 0x02400240, 0x02400240, 0x01400240, 0x000000c0, // ICON_FILTER - 0x00800000, 0x00800080, 0x00000080, 0x3c9e0000, 0x00000000, 0x00800080, 0x00800080, 0x00000000, // ICON_TARGET_POINT - 0x00800000, 0x00800080, 0x00800080, 0x3f7e01c0, 0x008001c0, 0x00800080, 0x00800080, 0x00000000, // ICON_TARGET_SMALL - 0x00800000, 0x00800080, 0x03e00080, 0x3e3e0220, 0x03e00220, 0x00800080, 0x00800080, 0x00000000, // ICON_TARGET_BIG - 0x01000000, 0x04400280, 0x01000100, 0x43842008, 0x43849ab2, 0x01002008, 0x04400100, 0x01000280, // ICON_TARGET_MOVE - 0x01000000, 0x04400280, 0x01000100, 0x41042108, 0x41049ff2, 0x01002108, 0x04400100, 0x01000280, // ICON_CURSOR_MOVE - 0x781e0000, 0x500a4002, 0x04204812, 0x00000240, 0x02400000, 0x48120420, 0x4002500a, 0x0000781e, // ICON_CURSOR_SCALE - 0x00000000, 0x20003c00, 0x24002800, 0x01000200, 0x00400080, 0x00140024, 0x003c0004, 0x00000000, // ICON_CURSOR_SCALE_RIGHT - 0x00000000, 0x0004003c, 0x00240014, 0x00800040, 0x02000100, 0x28002400, 0x3c002000, 0x00000000, // ICON_CURSOR_SCALE_LEFT - 0x00000000, 0x00100020, 0x10101fc8, 0x10001020, 0x10001000, 0x10001000, 0x00001fc0, 0x00000000, // ICON_UNDO - 0x00000000, 0x08000400, 0x080813f8, 0x00080408, 0x00080008, 0x00080008, 0x000003f8, 0x00000000, // ICON_REDO - 0x00000000, 0x3ffc0000, 0x20042004, 0x20002000, 0x20402000, 0x3f902020, 0x00400020, 0x00000000, // ICON_REREDO - 0x00000000, 0x3ffc0000, 0x20042004, 0x27fc2004, 0x20202000, 0x3fc82010, 0x00200010, 0x00000000, // ICON_MUTATE - 0x00000000, 0x0ff00000, 0x10081818, 0x11801008, 0x10001180, 0x18101020, 0x00100fc8, 0x00000020, // ICON_ROTATE - 0x00000000, 0x04000200, 0x240429fc, 0x20042204, 0x20442004, 0x3f942024, 0x00400020, 0x00000000, // ICON_REPEAT - 0x00000000, 0x20001000, 0x22104c0e, 0x00801120, 0x11200040, 0x4c0e2210, 0x10002000, 0x00000000, // ICON_SHUFFLE - 0x7ffe0000, 0x50024002, 0x44024802, 0x41024202, 0x40424082, 0x40124022, 0x4002400a, 0x00007ffe, // ICON_EMPTYBOX - 0x00800000, 0x03e00080, 0x08080490, 0x3c9e0808, 0x08080808, 0x03e00490, 0x00800080, 0x00000000, // ICON_TARGET - 0x00800000, 0x00800080, 0x00800080, 0x3ffe01c0, 0x008001c0, 0x00800080, 0x00800080, 0x00000000, // ICON_TARGET_SMALL_FILL - 0x00800000, 0x00800080, 0x03e00080, 0x3ffe03e0, 0x03e003e0, 0x00800080, 0x00800080, 0x00000000, // ICON_TARGET_BIG_FILL - 0x01000000, 0x07c00380, 0x01000100, 0x638c2008, 0x638cfbbe, 0x01002008, 0x07c00100, 0x01000380, // ICON_TARGET_MOVE_FILL - 0x01000000, 0x07c00380, 0x01000100, 0x610c2108, 0x610cfffe, 0x01002108, 0x07c00100, 0x01000380, // ICON_CURSOR_MOVE_FILL - 0x781e0000, 0x6006700e, 0x04204812, 0x00000240, 0x02400000, 0x48120420, 0x700e6006, 0x0000781e, // ICON_CURSOR_SCALE_FILL - 0x00000000, 0x38003c00, 0x24003000, 0x01000200, 0x00400080, 0x000c0024, 0x003c001c, 0x00000000, // ICON_CURSOR_SCALE_RIGHT_FILL - 0x00000000, 0x001c003c, 0x0024000c, 0x00800040, 0x02000100, 0x30002400, 0x3c003800, 0x00000000, // ICON_CURSOR_SCALE_LEFT_FILL - 0x00000000, 0x00300020, 0x10301ff8, 0x10001020, 0x10001000, 0x10001000, 0x00001fc0, 0x00000000, // ICON_UNDO_FILL - 0x00000000, 0x0c000400, 0x0c081ff8, 0x00080408, 0x00080008, 0x00080008, 0x000003f8, 0x00000000, // ICON_REDO_FILL - 0x00000000, 0x3ffc0000, 0x20042004, 0x20002000, 0x20402000, 0x3ff02060, 0x00400060, 0x00000000, // ICON_REREDO_FILL - 0x00000000, 0x3ffc0000, 0x20042004, 0x27fc2004, 0x20202000, 0x3ff82030, 0x00200030, 0x00000000, // ICON_MUTATE_FILL - 0x00000000, 0x0ff00000, 0x10081818, 0x11801008, 0x10001180, 0x18301020, 0x00300ff8, 0x00000020, // ICON_ROTATE_FILL - 0x00000000, 0x06000200, 0x26042ffc, 0x20042204, 0x20442004, 0x3ff42064, 0x00400060, 0x00000000, // ICON_REPEAT_FILL - 0x00000000, 0x30001000, 0x32107c0e, 0x00801120, 0x11200040, 0x7c0e3210, 0x10003000, 0x00000000, // ICON_SHUFFLE_FILL - 0x00000000, 0x30043ffc, 0x24042804, 0x21042204, 0x20442084, 0x20142024, 0x3ffc200c, 0x00000000, // ICON_EMPTYBOX_SMALL - 0x00000000, 0x20043ffc, 0x20042004, 0x20042004, 0x20042004, 0x20042004, 0x3ffc2004, 0x00000000, // ICON_BOX - 0x00000000, 0x23c43ffc, 0x23c423c4, 0x200423c4, 0x20042004, 0x20042004, 0x3ffc2004, 0x00000000, // ICON_BOX_TOP - 0x00000000, 0x3e043ffc, 0x3e043e04, 0x20043e04, 0x20042004, 0x20042004, 0x3ffc2004, 0x00000000, // ICON_BOX_TOP_RIGHT - 0x00000000, 0x20043ffc, 0x20042004, 0x3e043e04, 0x3e043e04, 0x20042004, 0x3ffc2004, 0x00000000, // ICON_BOX_RIGHT - 0x00000000, 0x20043ffc, 0x20042004, 0x20042004, 0x3e042004, 0x3e043e04, 0x3ffc3e04, 0x00000000, // ICON_BOX_BOTTOM_RIGHT - 0x00000000, 0x20043ffc, 0x20042004, 0x20042004, 0x23c42004, 0x23c423c4, 0x3ffc23c4, 0x00000000, // ICON_BOX_BOTTOM - 0x00000000, 0x20043ffc, 0x20042004, 0x20042004, 0x207c2004, 0x207c207c, 0x3ffc207c, 0x00000000, // ICON_BOX_BOTTOM_LEFT - 0x00000000, 0x20043ffc, 0x20042004, 0x207c207c, 0x207c207c, 0x20042004, 0x3ffc2004, 0x00000000, // ICON_BOX_LEFT - 0x00000000, 0x207c3ffc, 0x207c207c, 0x2004207c, 0x20042004, 0x20042004, 0x3ffc2004, 0x00000000, // ICON_BOX_TOP_LEFT - 0x00000000, 0x20043ffc, 0x20042004, 0x23c423c4, 0x23c423c4, 0x20042004, 0x3ffc2004, 0x00000000, // ICON_BOX_CENTER - 0x7ffe0000, 0x40024002, 0x47e24182, 0x4ff247e2, 0x47e24ff2, 0x418247e2, 0x40024002, 0x00007ffe, // ICON_BOX_CIRCLE_MASK - 0x7fff0000, 0x40014001, 0x40014001, 0x49555ddd, 0x4945495d, 0x400149c5, 0x40014001, 0x00007fff, // ICON_POT - 0x7ffe0000, 0x53327332, 0x44ce4cce, 0x41324332, 0x404e40ce, 0x48125432, 0x4006540e, 0x00007ffe, // ICON_ALPHA_MULTIPLY - 0x7ffe0000, 0x53327332, 0x44ce4cce, 0x41324332, 0x5c4e40ce, 0x44124432, 0x40065c0e, 0x00007ffe, // ICON_ALPHA_CLEAR - 0x7ffe0000, 0x42fe417e, 0x42fe417e, 0x42fe417e, 0x42fe417e, 0x42fe417e, 0x42fe417e, 0x00007ffe, // ICON_DITHERING - 0x07fe0000, 0x1ffa0002, 0x7fea000a, 0x402a402a, 0x5b2a512a, 0x5128552a, 0x40205128, 0x00007fe0, // ICON_MIPMAPS - 0x00000000, 0x1ff80000, 0x12481248, 0x12481ff8, 0x1ff81248, 0x12481248, 0x00001ff8, 0x00000000, // ICON_BOX_GRID - 0x12480000, 0x7ffe1248, 0x12481248, 0x12487ffe, 0x7ffe1248, 0x12481248, 0x12487ffe, 0x00001248, // ICON_GRID - 0x00000000, 0x1c380000, 0x1c3817e8, 0x08100810, 0x08100810, 0x17e81c38, 0x00001c38, 0x00000000, // ICON_BOX_CORNERS_SMALL - 0x700e0000, 0x700e5ffa, 0x20042004, 0x20042004, 0x20042004, 0x20042004, 0x5ffa700e, 0x0000700e, // ICON_BOX_CORNERS_BIG - 0x3f7e0000, 0x21422142, 0x21422142, 0x00003f7e, 0x21423f7e, 0x21422142, 0x3f7e2142, 0x00000000, // ICON_FOUR_BOXES - 0x00000000, 0x3bb80000, 0x3bb83bb8, 0x3bb80000, 0x3bb83bb8, 0x3bb80000, 0x3bb83bb8, 0x00000000, // ICON_GRID_FILL - 0x7ffe0000, 0x7ffe7ffe, 0x77fe7000, 0x77fe77fe, 0x777e7700, 0x777e777e, 0x777e777e, 0x0000777e, // ICON_BOX_MULTISIZE - 0x781e0000, 0x40024002, 0x00004002, 0x01800000, 0x00000180, 0x40020000, 0x40024002, 0x0000781e, // ICON_ZOOM_SMALL - 0x781e0000, 0x40024002, 0x00004002, 0x03c003c0, 0x03c003c0, 0x40020000, 0x40024002, 0x0000781e, // ICON_ZOOM_MEDIUM - 0x781e0000, 0x40024002, 0x07e04002, 0x07e007e0, 0x07e007e0, 0x400207e0, 0x40024002, 0x0000781e, // ICON_ZOOM_BIG - 0x781e0000, 0x5ffa4002, 0x1ff85ffa, 0x1ff81ff8, 0x1ff81ff8, 0x5ffa1ff8, 0x40025ffa, 0x0000781e, // ICON_ZOOM_ALL - 0x00000000, 0x2004381c, 0x00002004, 0x00000000, 0x00000000, 0x20040000, 0x381c2004, 0x00000000, // ICON_ZOOM_CENTER - 0x00000000, 0x1db80000, 0x10081008, 0x10080000, 0x00001008, 0x10081008, 0x00001db8, 0x00000000, // ICON_BOX_DOTS_SMALL - 0x35560000, 0x00002002, 0x00002002, 0x00002002, 0x00002002, 0x00002002, 0x35562002, 0x00000000, // ICON_BOX_DOTS_BIG - 0x7ffe0000, 0x40024002, 0x48124ff2, 0x49924812, 0x48124992, 0x4ff24812, 0x40024002, 0x00007ffe, // ICON_BOX_CONCENTRIC - 0x00000000, 0x10841ffc, 0x10841084, 0x1ffc1084, 0x10841084, 0x10841084, 0x00001ffc, 0x00000000, // ICON_BOX_GRID_BIG - 0x00000000, 0x00000000, 0x10000000, 0x04000800, 0x01040200, 0x00500088, 0x00000020, 0x00000000, // ICON_OK_TICK - 0x00000000, 0x10080000, 0x04200810, 0x01800240, 0x02400180, 0x08100420, 0x00001008, 0x00000000, // ICON_CROSS - 0x00000000, 0x02000000, 0x00800100, 0x00200040, 0x00200010, 0x00800040, 0x02000100, 0x00000000, // ICON_ARROW_LEFT - 0x00000000, 0x00400000, 0x01000080, 0x04000200, 0x04000800, 0x01000200, 0x00400080, 0x00000000, // ICON_ARROW_RIGHT - 0x00000000, 0x00000000, 0x00000000, 0x08081004, 0x02200410, 0x00800140, 0x00000000, 0x00000000, // ICON_ARROW_DOWN - 0x00000000, 0x00000000, 0x01400080, 0x04100220, 0x10040808, 0x00000000, 0x00000000, 0x00000000, // ICON_ARROW_UP - 0x00000000, 0x02000000, 0x03800300, 0x03e003c0, 0x03e003f0, 0x038003c0, 0x02000300, 0x00000000, // ICON_ARROW_LEFT_FILL - 0x00000000, 0x00400000, 0x01c000c0, 0x07c003c0, 0x07c00fc0, 0x01c003c0, 0x004000c0, 0x00000000, // ICON_ARROW_RIGHT_FILL - 0x00000000, 0x00000000, 0x00000000, 0x0ff81ffc, 0x03e007f0, 0x008001c0, 0x00000000, 0x00000000, // ICON_ARROW_DOWN_FILL - 0x00000000, 0x00000000, 0x01c00080, 0x07f003e0, 0x1ffc0ff8, 0x00000000, 0x00000000, 0x00000000, // ICON_ARROW_UP_FILL - 0x00000000, 0x18a008c0, 0x32881290, 0x24822686, 0x26862482, 0x12903288, 0x08c018a0, 0x00000000, // ICON_AUDIO - 0x00000000, 0x04800780, 0x004000c0, 0x662000f0, 0x08103c30, 0x130a0e18, 0x0000318e, 0x00000000, // ICON_FX - 0x00000000, 0x00800000, 0x08880888, 0x2aaa0a8a, 0x0a8a2aaa, 0x08880888, 0x00000080, 0x00000000, // ICON_WAVE - 0x00000000, 0x00600000, 0x01080090, 0x02040108, 0x42044204, 0x24022402, 0x00001800, 0x00000000, // ICON_WAVE_SINUS - 0x00000000, 0x07f80000, 0x04080408, 0x04080408, 0x04080408, 0x7c0e0408, 0x00000000, 0x00000000, // ICON_WAVE_SQUARE - 0x00000000, 0x00000000, 0x00a00040, 0x22084110, 0x08021404, 0x00000000, 0x00000000, 0x00000000, // ICON_WAVE_TRIANGULAR - 0x00000000, 0x00000000, 0x04200000, 0x01800240, 0x02400180, 0x00000420, 0x00000000, 0x00000000, // ICON_CROSS_SMALL - 0x00000000, 0x18380000, 0x12281428, 0x10a81128, 0x112810a8, 0x14281228, 0x00001838, 0x00000000, // ICON_PLAYER_PREVIOUS - 0x00000000, 0x18000000, 0x11801600, 0x10181060, 0x10601018, 0x16001180, 0x00001800, 0x00000000, // ICON_PLAYER_PLAY_BACK - 0x00000000, 0x00180000, 0x01880068, 0x18080608, 0x06081808, 0x00680188, 0x00000018, 0x00000000, // ICON_PLAYER_PLAY - 0x00000000, 0x1e780000, 0x12481248, 0x12481248, 0x12481248, 0x12481248, 0x00001e78, 0x00000000, // ICON_PLAYER_PAUSE - 0x00000000, 0x1ff80000, 0x10081008, 0x10081008, 0x10081008, 0x10081008, 0x00001ff8, 0x00000000, // ICON_PLAYER_STOP - 0x00000000, 0x1c180000, 0x14481428, 0x15081488, 0x14881508, 0x14281448, 0x00001c18, 0x00000000, // ICON_PLAYER_NEXT - 0x00000000, 0x03c00000, 0x08100420, 0x10081008, 0x10081008, 0x04200810, 0x000003c0, 0x00000000, // ICON_PLAYER_RECORD - 0x00000000, 0x0c3007e0, 0x13c81818, 0x14281668, 0x14281428, 0x1c381c38, 0x08102244, 0x00000000, // ICON_MAGNET - 0x07c00000, 0x08200820, 0x3ff80820, 0x23882008, 0x21082388, 0x20082108, 0x1ff02008, 0x00000000, // ICON_LOCK_CLOSE - 0x07c00000, 0x08000800, 0x3ff80800, 0x23882008, 0x21082388, 0x20082108, 0x1ff02008, 0x00000000, // ICON_LOCK_OPEN - 0x01c00000, 0x0c180770, 0x3086188c, 0x60832082, 0x60034781, 0x30062002, 0x0c18180c, 0x01c00770, // ICON_CLOCK - 0x0a200000, 0x1b201b20, 0x04200e20, 0x04200420, 0x04700420, 0x0e700e70, 0x0e700e70, 0x04200e70, // ICON_TOOLS - 0x01800000, 0x3bdc318c, 0x0ff01ff8, 0x7c3e1e78, 0x1e787c3e, 0x1ff80ff0, 0x318c3bdc, 0x00000180, // ICON_GEAR - 0x01800000, 0x3ffc318c, 0x1c381ff8, 0x781e1818, 0x1818781e, 0x1ff81c38, 0x318c3ffc, 0x00000180, // ICON_GEAR_BIG - 0x00000000, 0x08080ff8, 0x08081ffc, 0x0aa80aa8, 0x0aa80aa8, 0x0aa80aa8, 0x08080aa8, 0x00000ff8, // ICON_BIN - 0x00000000, 0x00000000, 0x20043ffc, 0x08043f84, 0x04040f84, 0x04040784, 0x000007fc, 0x00000000, // ICON_HAND_POINTER - 0x00000000, 0x24400400, 0x00001480, 0x6efe0e00, 0x00000e00, 0x24401480, 0x00000400, 0x00000000, // ICON_LASER - 0x00000000, 0x03c00000, 0x08300460, 0x11181118, 0x11181118, 0x04600830, 0x000003c0, 0x00000000, // ICON_COIN - 0x00000000, 0x10880080, 0x06c00810, 0x366c07e0, 0x07e00240, 0x00001768, 0x04200240, 0x00000000, // ICON_EXPLOSION - 0x00000000, 0x3d280000, 0x2528252c, 0x3d282528, 0x05280528, 0x05e80528, 0x00000000, 0x00000000, // ICON_1UP - 0x01800000, 0x03c003c0, 0x018003c0, 0x0ff007e0, 0x0bd00bd0, 0x0a500bd0, 0x02400240, 0x02400240, // ICON_PLAYER - 0x01800000, 0x03c003c0, 0x118013c0, 0x03c81ff8, 0x07c003c8, 0x04400440, 0x0c080478, 0x00000000, // ICON_PLAYER_JUMP - 0x3ff80000, 0x30183ff8, 0x30183018, 0x3ff83ff8, 0x03000300, 0x03c003c0, 0x03e00300, 0x000003e0, // ICON_KEY - 0x3ff80000, 0x3ff83ff8, 0x33983ff8, 0x3ff83398, 0x3ff83ff8, 0x00000540, 0x0fe00aa0, 0x00000fe0, // ICON_DEMON - 0x00000000, 0x0ff00000, 0x20041008, 0x25442004, 0x10082004, 0x06000bf0, 0x00000300, 0x00000000, // ICON_TEXT_POPUP - 0x00000000, 0x11440000, 0x07f00be8, 0x1c1c0e38, 0x1c1c0c18, 0x07f00e38, 0x11440be8, 0x00000000, // ICON_GEAR_EX - 0x00000000, 0x20080000, 0x0c601010, 0x07c00fe0, 0x07c007c0, 0x0c600fe0, 0x20081010, 0x00000000, // ICON_CRACK - 0x00000000, 0x20080000, 0x0c601010, 0x04400fe0, 0x04405554, 0x0c600fe0, 0x20081010, 0x00000000, // ICON_CRACK_POINTS - 0x00000000, 0x00800080, 0x01c001c0, 0x1ffc3ffe, 0x03e007f0, 0x07f003e0, 0x0c180770, 0x00000808, // ICON_STAR - 0x0ff00000, 0x08180810, 0x08100818, 0x0a100810, 0x08180810, 0x08100818, 0x08100810, 0x00001ff8, // ICON_DOOR - 0x0ff00000, 0x08100810, 0x08100810, 0x10100010, 0x4f902010, 0x10102010, 0x08100010, 0x00000ff0, // ICON_EXIT - 0x00040000, 0x001f000e, 0x0ef40004, 0x12f41284, 0x0ef41214, 0x10040004, 0x7ffc3004, 0x10003000, // ICON_MODE_2D - 0x78040000, 0x501f600e, 0x0ef44004, 0x12f41284, 0x0ef41284, 0x10140004, 0x7ffc300c, 0x10003000, // ICON_MODE_3D - 0x7fe00000, 0x50286030, 0x47fe4804, 0x44224402, 0x44224422, 0x241275e2, 0x0c06140a, 0x000007fe, // ICON_CUBE - 0x7fe00000, 0x5ff87ff0, 0x47fe4ffc, 0x44224402, 0x44224422, 0x241275e2, 0x0c06140a, 0x000007fe, // ICON_CUBE_FACE_TOP - 0x7fe00000, 0x50386030, 0x47c2483c, 0x443e443e, 0x443e443e, 0x241e75fe, 0x0c06140e, 0x000007fe, // ICON_CUBE_FACE_LEFT - 0x7fe00000, 0x50286030, 0x47fe4804, 0x47fe47fe, 0x47fe47fe, 0x27fe77fe, 0x0ffe17fe, 0x000007fe, // ICON_CUBE_FACE_FRONT - 0x7fe00000, 0x50286030, 0x47fe4804, 0x44224402, 0x44224422, 0x3bf27be2, 0x0bfe1bfa, 0x000007fe, // ICON_CUBE_FACE_BOTTOM - 0x7fe00000, 0x70286030, 0x7ffe7804, 0x7c227c02, 0x7c227c22, 0x3c127de2, 0x0c061c0a, 0x000007fe, // ICON_CUBE_FACE_RIGHT - 0x7fe00000, 0x6fe85ff0, 0x781e77e4, 0x7be27be2, 0x7be27be2, 0x24127be2, 0x0c06140a, 0x000007fe, // ICON_CUBE_FACE_BACK - 0x00000000, 0x2a0233fe, 0x22022602, 0x22022202, 0x2a022602, 0x00a033fe, 0x02080110, 0x00000000, // ICON_CAMERA - 0x00000000, 0x200c3ffc, 0x000c000c, 0x3ffc000c, 0x30003000, 0x30003000, 0x3ffc3004, 0x00000000, // ICON_SPECIAL - 0x00000000, 0x0022003e, 0x012201e2, 0x0100013e, 0x01000100, 0x79000100, 0x4f004900, 0x00007800, // ICON_LINK_NET - 0x00000000, 0x44007c00, 0x45004600, 0x00627cbe, 0x00620022, 0x45007cbe, 0x44004600, 0x00007c00, // ICON_LINK_BOXES - 0x00000000, 0x0044007c, 0x0010007c, 0x3f100010, 0x3f1021f0, 0x3f100010, 0x3f0021f0, 0x00000000, // ICON_LINK_MULTI - 0x00000000, 0x0044007c, 0x00440044, 0x0010007c, 0x00100010, 0x44107c10, 0x440047f0, 0x00007c00, // ICON_LINK - 0x00000000, 0x0044007c, 0x00440044, 0x0000007c, 0x00000010, 0x44007c10, 0x44004550, 0x00007c00, // ICON_LINK_BROKE - 0x02a00000, 0x22a43ffc, 0x20042004, 0x20042ff4, 0x20042ff4, 0x20042ff4, 0x20042004, 0x00003ffc, // ICON_TEXT_NOTES - 0x3ffc0000, 0x20042004, 0x245e27c4, 0x27c42444, 0x2004201e, 0x201e2004, 0x20042004, 0x00003ffc, // ICON_NOTEBOOK - 0x00000000, 0x07e00000, 0x04200420, 0x24243ffc, 0x24242424, 0x24242424, 0x3ffc2424, 0x00000000, // ICON_SUITCASE - 0x00000000, 0x0fe00000, 0x08200820, 0x40047ffc, 0x7ffc5554, 0x40045554, 0x7ffc4004, 0x00000000, // ICON_SUITCASE_ZIP - 0x00000000, 0x20043ffc, 0x3ffc2004, 0x13c81008, 0x100813c8, 0x10081008, 0x1ff81008, 0x00000000, // ICON_MAILBOX - 0x00000000, 0x40027ffe, 0x5ffa5ffa, 0x5ffa5ffa, 0x40025ffa, 0x03c07ffe, 0x1ff81ff8, 0x00000000, // ICON_MONITOR - 0x0ff00000, 0x6bfe7ffe, 0x7ffe7ffe, 0x68167ffe, 0x08106816, 0x08100810, 0x0ff00810, 0x00000000, // ICON_PRINTER - 0x3ff80000, 0xfffe2008, 0x870a8002, 0x904a888a, 0x904a904a, 0x870a888a, 0xfffe8002, 0x00000000, // ICON_PHOTO_CAMERA - 0x0fc00000, 0xfcfe0cd8, 0x8002fffe, 0x84428382, 0x84428442, 0x80028382, 0xfffe8002, 0x00000000, // ICON_PHOTO_CAMERA_FLASH - 0x00000000, 0x02400180, 0x08100420, 0x20041008, 0x23c42004, 0x22442244, 0x3ffc2244, 0x00000000, // ICON_HOUSE - 0x00000000, 0x1c700000, 0x3ff83ef8, 0x3ff83ff8, 0x0fe01ff0, 0x038007c0, 0x00000100, 0x00000000, // ICON_HEART - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x80000000, 0xe000c000, // ICON_CORNER - 0x00000000, 0x14001c00, 0x15c01400, 0x15401540, 0x155c1540, 0x15541554, 0x1ddc1554, 0x00000000, // ICON_VERTICAL_BARS - 0x00000000, 0x03000300, 0x1b001b00, 0x1b601b60, 0x1b6c1b60, 0x1b6c1b6c, 0x1b6c1b6c, 0x00000000, // ICON_VERTICAL_BARS_FILL - 0x00000000, 0x00000000, 0x403e7ffe, 0x7ffe403e, 0x7ffe0000, 0x43fe43fe, 0x00007ffe, 0x00000000, // ICON_LIFE_BARS - 0x7ffc0000, 0x43844004, 0x43844284, 0x43844004, 0x42844284, 0x42844284, 0x40044384, 0x00007ffc, // ICON_INFO - 0x40008000, 0x10002000, 0x04000800, 0x01000200, 0x00400080, 0x00100020, 0x00040008, 0x00010002, // ICON_CROSSLINE - 0x00000000, 0x1ff01ff0, 0x18301830, 0x1f001830, 0x03001f00, 0x00000300, 0x03000300, 0x00000000, // ICON_HELP - 0x3ff00000, 0x2abc3550, 0x2aac3554, 0x2aac3554, 0x2aac3554, 0x2aac3554, 0x2aac3554, 0x00003ffc, // ICON_FILETYPE_ALPHA - 0x3ff00000, 0x201c2010, 0x22442184, 0x28142424, 0x29942814, 0x2ff42994, 0x20042004, 0x00003ffc, // ICON_FILETYPE_HOME - 0x07fe0000, 0x04020402, 0x7fe20402, 0x44224422, 0x44224422, 0x402047fe, 0x40204020, 0x00007fe0, // ICON_LAYERS_VISIBLE - 0x07fe0000, 0x04020402, 0x7c020402, 0x44024402, 0x44024402, 0x402047fe, 0x40204020, 0x00007fe0, // ICON_LAYERS - 0x00000000, 0x40027ffe, 0x7ffe4002, 0x40024002, 0x40024002, 0x40024002, 0x7ffe4002, 0x00000000, // ICON_WINDOW - 0x09100000, 0x09f00910, 0x09100910, 0x00000910, 0x24a2779e, 0x27a224a2, 0x709e20a2, 0x00000000, // ICON_HIDPI - 0x3ff00000, 0x201c2010, 0x2a842e84, 0x2e842a84, 0x2ba42004, 0x2aa42aa4, 0x20042ba4, 0x00003ffc, // ICON_FILETYPE_BINARY - 0x00000000, 0x00000000, 0x00120012, 0x4a5e4bd2, 0x485233d2, 0x00004bd2, 0x00000000, 0x00000000, // ICON_HEX - 0x01800000, 0x381c0660, 0x23c42004, 0x23c42044, 0x13c82204, 0x08101008, 0x02400420, 0x00000180, // ICON_SHIELD - 0x007e0000, 0x20023fc2, 0x40227fe2, 0x400a403a, 0x400a400a, 0x400a400a, 0x4008400e, 0x00007ff8, // ICON_FILE_NEW - 0x00000000, 0x0042007e, 0x40027fc2, 0x44024002, 0x5f024402, 0x44024402, 0x7ffe4002, 0x00000000, // ICON_FOLDER_ADD - 0x44220000, 0x12482244, 0xf3cf0000, 0x14280420, 0x48122424, 0x08100810, 0x1ff81008, 0x03c00420, // ICON_ALARM - 0x0aa00000, 0x1ff80aa0, 0x1068700e, 0x1008706e, 0x1008700e, 0x1008700e, 0x0aa01ff8, 0x00000aa0, // ICON_CPU - 0x07e00000, 0x04201db8, 0x04a01c38, 0x04a01d38, 0x04a01d38, 0x04a01d38, 0x04201d38, 0x000007e0, // ICON_ROM - 0x00000000, 0x03c00000, 0x3c382ff0, 0x3c04380c, 0x01800000, 0x03c003c0, 0x00000180, 0x00000000, // ICON_STEP_OVER - 0x01800000, 0x01800180, 0x01800180, 0x03c007e0, 0x00000180, 0x01800000, 0x03c003c0, 0x00000180, // ICON_STEP_INTO - 0x01800000, 0x07e003c0, 0x01800180, 0x01800180, 0x00000180, 0x01800000, 0x03c003c0, 0x00000180, // ICON_STEP_OUT - 0x00000000, 0x0ff003c0, 0x181c1c34, 0x303c301c, 0x30003000, 0x1c301800, 0x03c00ff0, 0x00000000, // ICON_RESTART - 0x00000000, 0x00000000, 0x07e003c0, 0x0ff00ff0, 0x0ff00ff0, 0x03c007e0, 0x00000000, 0x00000000, // ICON_BREAKPOINT_ON - 0x00000000, 0x00000000, 0x042003c0, 0x08100810, 0x08100810, 0x03c00420, 0x00000000, 0x00000000, // ICON_BREAKPOINT_OFF - 0x00000000, 0x00000000, 0x1ff81ff8, 0x1ff80000, 0x00001ff8, 0x1ff81ff8, 0x00000000, 0x00000000, // ICON_BURGER_MENU - 0x00000000, 0x00000000, 0x00880070, 0x0c880088, 0x1e8810f8, 0x3e881288, 0x00000000, 0x00000000, // ICON_CASE_SENSITIVE - 0x00000000, 0x02000000, 0x07000a80, 0x07001fc0, 0x02000a80, 0x00300030, 0x00000000, 0x00000000, // ICON_REG_EXP - 0x00000000, 0x0042007e, 0x40027fc2, 0x40024002, 0x40024002, 0x40024002, 0x7ffe4002, 0x00000000, // ICON_FOLDER - 0x3ff00000, 0x201c2010, 0x20042004, 0x20042004, 0x20042004, 0x20042004, 0x20042004, 0x00003ffc, // ICON_FILE - 0x1ff00000, 0x20082008, 0x17d02fe8, 0x05400ba0, 0x09200540, 0x23881010, 0x2fe827c8, 0x00001ff0, // ICON_SAND_TIMER - 0x01800000, 0x02400240, 0x05a00420, 0x09900990, 0x11881188, 0x21842004, 0x40024182, 0x00003ffc, // ICON_WARNING - 0x7ffe0000, 0x4ff24002, 0x4c324ff2, 0x4f824c02, 0x41824f82, 0x41824002, 0x40024182, 0x00007ffe, // ICON_HELP_BOX - 0x7ffe0000, 0x41824002, 0x40024182, 0x41824182, 0x41824182, 0x41824182, 0x40024182, 0x00007ffe, // ICON_INFO_BOX - 0x01800000, 0x04200240, 0x10080810, 0x7bde2004, 0x0a500a50, 0x08500bd0, 0x08100850, 0x00000ff0, // ICON_PRIORITY - 0x01800000, 0x18180660, 0x80016006, 0x98196006, 0x99996666, 0x19986666, 0x01800660, 0x00000000, // ICON_LAYERS_ISO - 0x07fe0000, 0x1c020402, 0x74021402, 0x54025402, 0x54025402, 0x500857fe, 0x40205ff8, 0x00007fe0, // ICON_LAYERS2 - 0x0ffe0000, 0x3ffa0802, 0x7fea200a, 0x402a402a, 0x422a422a, 0x422e422a, 0x40384e28, 0x00007fe0, // ICON_MLAYERS - 0x0ffe0000, 0x3ffa0802, 0x7fea200a, 0x402a402a, 0x5b2a512a, 0x512e552a, 0x40385128, 0x00007fe0, // ICON_MAPS - 0x04200000, 0x1cf00c60, 0x11f019f0, 0x0f3807b8, 0x1e3c0f3c, 0x1c1c1e1c, 0x1e3c1c1c, 0x00000f70, // ICON_HOT - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, // ICON_229 - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, // ICON_230 - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, // ICON_231 - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, // ICON_232 - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, // ICON_233 - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, // ICON_234 - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, // ICON_235 - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, // ICON_236 - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, // ICON_237 - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, // ICON_238 - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, // ICON_239 - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, // ICON_240 - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, // ICON_241 - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, // ICON_242 - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, // ICON_243 - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, // ICON_244 - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, // ICON_245 - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, // ICON_246 - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, // ICON_247 - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, // ICON_248 - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, // ICON_249 - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, // ICON_250 - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, // ICON_251 - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, // ICON_252 - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, // ICON_253 - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, // ICON_254 - 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, // ICON_255 -}; - -// NOTE: A pointer to current icons array should be defined -static unsigned int *guiIconsPtr = guiIcons; - -#endif // !RAYGUI_NO_ICONS && !RAYGUI_CUSTOM_ICONS - -#ifndef RAYGUI_ICON_SIZE - #define RAYGUI_ICON_SIZE 0 -#endif - -// WARNING: Those values define the total size of the style data array, -// if changed, previous saved styles could become incompatible -#define RAYGUI_MAX_CONTROLS 16 // Maximum number of controls -#define RAYGUI_MAX_PROPS_BASE 16 // Maximum number of base properties -#define RAYGUI_MAX_PROPS_EXTENDED 8 // Maximum number of extended properties - -//---------------------------------------------------------------------------------- -// Types and Structures Definition -//---------------------------------------------------------------------------------- -// Gui control property style color element -typedef enum { BORDER = 0, BASE, TEXT, OTHER } GuiPropertyElement; - -//---------------------------------------------------------------------------------- -// Global Variables Definition -//---------------------------------------------------------------------------------- -static GuiState guiState = STATE_NORMAL; // Gui global state, if !STATE_NORMAL, forces defined state - -static Font guiFont = { 0 }; // Gui current font (WARNING: highly coupled to raylib) -static bool guiLocked = false; // Gui lock state (no inputs processed) -static float guiAlpha = 1.0f; // Gui controls transparency - -static unsigned int guiIconScale = 1; // Gui icon default scale (if icons enabled) - -static bool guiTooltip = false; // Tooltip enabled/disabled -static const char *guiTooltipPtr = NULL; // Tooltip string pointer (string provided by user) - -static bool guiControlExclusiveMode = false; // Gui control exclusive mode (no inputs processed except current control) -static Rectangle guiControlExclusiveRec = { 0 }; // Gui control exclusive bounds rectangle, used as an unique identifier - -static int textBoxCursorIndex = 0; // Cursor index, shared by all GuiTextBox*() -//static int blinkCursorFrameCounter = 0; // Frame counter for cursor blinking -static int autoCursorCooldownCounter = 0; // Cooldown frame counter for automatic cursor movement on key-down -static int autoCursorDelayCounter = 0; // Delay frame counter for automatic cursor movement - -//---------------------------------------------------------------------------------- -// Style data array for all gui style properties (allocated on data segment by default) -// -// NOTE 1: First set of BASE properties are generic to all controls but could be individually -// overwritten per control, first set of EXTENDED properties are generic to all controls and -// can not be overwritten individually but custom EXTENDED properties can be used by control -// -// NOTE 2: A new style set could be loaded over this array using GuiLoadStyle(), -// but default gui style could always be recovered with GuiLoadStyleDefault() -// -// guiStyle size is by default: 16*(16 + 8) = 384*4 = 1536 bytes = 1.5 KB -//---------------------------------------------------------------------------------- -static unsigned int guiStyle[RAYGUI_MAX_CONTROLS*(RAYGUI_MAX_PROPS_BASE + RAYGUI_MAX_PROPS_EXTENDED)] = { 0 }; - -static bool guiStyleLoaded = false; // Style loaded flag for lazy style initialization - -//---------------------------------------------------------------------------------- -// Standalone Mode Functions Declaration -// -// NOTE: raygui depend on some raylib input and drawing functions -// To use raygui as standalone library, below functions must be defined by the user -//---------------------------------------------------------------------------------- -#if defined(RAYGUI_STANDALONE) - -#define KEY_RIGHT 262 -#define KEY_LEFT 263 -#define KEY_DOWN 264 -#define KEY_UP 265 -#define KEY_BACKSPACE 259 -#define KEY_ENTER 257 - -#define MOUSE_LEFT_BUTTON 0 - -// Input required functions -//------------------------------------------------------------------------------- -static Vector2 GetMousePosition(void); -static float GetMouseWheelMove(void); -static bool IsMouseButtonDown(int button); -static bool IsMouseButtonPressed(int button); -static bool IsMouseButtonReleased(int button); - -static bool IsKeyDown(int key); -static bool IsKeyPressed(int key); -static int GetCharPressed(void); // -- GuiTextBox(), GuiValueBox() -//------------------------------------------------------------------------------- - -// Drawing required functions -//------------------------------------------------------------------------------- -static void DrawRectangle(int x, int y, int width, int height, Color color); // -- GuiDrawRectangle() -static void DrawRectangleGradientEx(Rectangle rec, Color col1, Color col2, Color col3, Color col4); // -- GuiColorPicker() -//------------------------------------------------------------------------------- - -// Text required functions -//------------------------------------------------------------------------------- -static Font GetFontDefault(void); // -- GuiLoadStyleDefault() -static Font LoadFontEx(const char *fileName, int fontSize, int *codepoints, int codepointCount); // -- GuiLoadStyle(), load font - -static Texture2D LoadTextureFromImage(Image image); // -- GuiLoadStyle(), required to load texture from embedded font atlas image -static void SetShapesTexture(Texture2D tex, Rectangle rec); // -- GuiLoadStyle(), required to set shapes rec to font white rec (optimization) - -static char *LoadFileText(const char *fileName); // -- GuiLoadStyle(), required to load charset data -static void UnloadFileText(char *text); // -- GuiLoadStyle(), required to unload charset data - -static const char *GetDirectoryPath(const char *filePath); // -- GuiLoadStyle(), required to find charset/font file from text .rgs - -static int *LoadCodepoints(const char *text, int *count); // -- GuiLoadStyle(), required to load required font codepoints list -static void UnloadCodepoints(int *codepoints); // -- GuiLoadStyle(), required to unload codepoints list - -static unsigned char *DecompressData(const unsigned char *compData, int compDataSize, int *dataSize); // -- GuiLoadStyle() -//------------------------------------------------------------------------------- - -// raylib functions already implemented in raygui -//------------------------------------------------------------------------------- -static Color GetColor(int hexValue); // Returns a Color struct from hexadecimal value -static int ColorToInt(Color color); // Returns hexadecimal value for a Color -static bool CheckCollisionPointRec(Vector2 point, Rectangle rec); // Check if point is inside rectangle -static const char *TextFormat(const char *text, ...); // Formatting of text with variables to 'embed' -static const char **TextSplit(const char *text, char delimiter, int *count); // Split text into multiple strings -static int TextToInteger(const char *text); // Get integer value from text -static float TextToFloat(const char *text); // Get float value from text - -static int GetCodepointNext(const char *text, int *codepointSize); // Get next codepoint in a UTF-8 encoded text -static const char *CodepointToUTF8(int codepoint, int *byteSize); // Encode codepoint into UTF-8 text (char array size returned as parameter) - -static void DrawRectangleGradientV(int posX, int posY, int width, int height, Color color1, Color color2); // Draw rectangle vertical gradient -//------------------------------------------------------------------------------- - -#endif // RAYGUI_STANDALONE - -//---------------------------------------------------------------------------------- -// Module specific Functions Declaration -//---------------------------------------------------------------------------------- -static void GuiLoadStyleFromMemory(const unsigned char *fileData, int dataSize); // Load style from memory (binary only) - -static int GetTextWidth(const char *text); // Gui get text width using gui font and style -static Rectangle GetTextBounds(int control, Rectangle bounds); // Get text bounds considering control bounds -static const char *GetTextIcon(const char *text, int *iconId); // Get text icon if provided and move text cursor - -static void GuiDrawText(const char *text, Rectangle textBounds, int alignment, Color tint); // Gui draw text using default font -static void GuiDrawRectangle(Rectangle rec, int borderWidth, Color borderColor, Color color); // Gui draw rectangle using default raygui style - -static const char **GuiTextSplit(const char *text, char delimiter, int *count, int *textRow); // Split controls text into multiple strings -static Vector3 ConvertHSVtoRGB(Vector3 hsv); // Convert color data from HSV to RGB -static Vector3 ConvertRGBtoHSV(Vector3 rgb); // Convert color data from RGB to HSV - -static int GuiScrollBar(Rectangle bounds, int value, int minValue, int maxValue); // Scroll bar control, used by GuiScrollPanel() -static void GuiTooltip(Rectangle controlRec); // Draw tooltip using control rec position - -static Color GuiFade(Color color, float alpha); // Fade color by an alpha factor - -//---------------------------------------------------------------------------------- -// Gui Setup Functions Definition -//---------------------------------------------------------------------------------- -// Enable gui global state -// NOTE: We check for STATE_DISABLED to avoid messing custom global state setups -void GuiEnable(void) { if (guiState == STATE_DISABLED) guiState = STATE_NORMAL; } - -// Disable gui global state -// NOTE: We check for STATE_NORMAL to avoid messing custom global state setups -void GuiDisable(void) { if (guiState == STATE_NORMAL) guiState = STATE_DISABLED; } - -// Lock gui global state -void GuiLock(void) { guiLocked = true; } - -// Unlock gui global state -void GuiUnlock(void) { guiLocked = false; } - -// Check if gui is locked (global state) -bool GuiIsLocked(void) { return guiLocked; } - -// Set gui controls alpha global state -void GuiSetAlpha(float alpha) -{ - if (alpha < 0.0f) alpha = 0.0f; - else if (alpha > 1.0f) alpha = 1.0f; - - guiAlpha = alpha; -} - -// Set gui state (global state) -void GuiSetState(int state) { guiState = (GuiState)state; } - -// Get gui state (global state) -int GuiGetState(void) { return guiState; } - -// Set custom gui font -// NOTE: Font loading/unloading is external to raygui -void GuiSetFont(Font font) -{ - if (font.texture.id > 0) - { - // NOTE: If we try to setup a font but default style has not been - // lazily loaded before, it will be overwritten, so we need to force - // default style loading first - if (!guiStyleLoaded) GuiLoadStyleDefault(); - - guiFont = font; - } -} - -// Get custom gui font -Font GuiGetFont(void) -{ - return guiFont; -} - -// Set control style property value -void GuiSetStyle(int control, int property, int value) -{ - if (!guiStyleLoaded) GuiLoadStyleDefault(); - guiStyle[control*(RAYGUI_MAX_PROPS_BASE + RAYGUI_MAX_PROPS_EXTENDED) + property] = value; - - // Default properties are propagated to all controls - if ((control == 0) && (property < RAYGUI_MAX_PROPS_BASE)) - { - for (int i = 1; i < RAYGUI_MAX_CONTROLS; i++) guiStyle[i*(RAYGUI_MAX_PROPS_BASE + RAYGUI_MAX_PROPS_EXTENDED) + property] = value; - } -} - -// Get control style property value -int GuiGetStyle(int control, int property) -{ - if (!guiStyleLoaded) GuiLoadStyleDefault(); - return guiStyle[control*(RAYGUI_MAX_PROPS_BASE + RAYGUI_MAX_PROPS_EXTENDED) + property]; -} - -//---------------------------------------------------------------------------------- -// Gui Controls Functions Definition -//---------------------------------------------------------------------------------- - -// Window Box control -int GuiWindowBox(Rectangle bounds, const char *title) -{ - // Window title bar height (including borders) - // NOTE: This define is also used by GuiMessageBox() and GuiTextInputBox() - #if !defined(RAYGUI_WINDOWBOX_STATUSBAR_HEIGHT) - #define RAYGUI_WINDOWBOX_STATUSBAR_HEIGHT 24 - #endif - - int result = 0; - //GuiState state = guiState; - - int statusBarHeight = RAYGUI_WINDOWBOX_STATUSBAR_HEIGHT; - - Rectangle statusBar = { bounds.x, bounds.y, bounds.width, (float)statusBarHeight }; - if (bounds.height < statusBarHeight*2.0f) bounds.height = statusBarHeight*2.0f; - - Rectangle windowPanel = { bounds.x, bounds.y + (float)statusBarHeight - 1, bounds.width, bounds.height - (float)statusBarHeight + 1 }; - Rectangle closeButtonRec = { statusBar.x + statusBar.width - GuiGetStyle(STATUSBAR, BORDER_WIDTH) - 20, - statusBar.y + statusBarHeight/2.0f - 18.0f/2.0f, 18, 18 }; - - // Update control - //-------------------------------------------------------------------- - // NOTE: Logic is directly managed by button - //-------------------------------------------------------------------- - - // Draw control - //-------------------------------------------------------------------- - GuiStatusBar(statusBar, title); // Draw window header as status bar - GuiPanel(windowPanel, NULL); // Draw window base - - // Draw window close button - int tempBorderWidth = GuiGetStyle(BUTTON, BORDER_WIDTH); - int tempTextAlignment = GuiGetStyle(BUTTON, TEXT_ALIGNMENT); - GuiSetStyle(BUTTON, BORDER_WIDTH, 1); - GuiSetStyle(BUTTON, TEXT_ALIGNMENT, TEXT_ALIGN_CENTER); -#if defined(RAYGUI_NO_ICONS) - result = GuiButton(closeButtonRec, "x"); -#else - result = GuiButton(closeButtonRec, GuiIconText(ICON_CROSS_SMALL, NULL)); -#endif - GuiSetStyle(BUTTON, BORDER_WIDTH, tempBorderWidth); - GuiSetStyle(BUTTON, TEXT_ALIGNMENT, tempTextAlignment); - //-------------------------------------------------------------------- - - return result; // Window close button clicked: result = 1 -} - -// Group Box control with text name -int GuiGroupBox(Rectangle bounds, const char *text) -{ - #if !defined(RAYGUI_GROUPBOX_LINE_THICK) - #define RAYGUI_GROUPBOX_LINE_THICK 1 - #endif - - int result = 0; - GuiState state = guiState; - - // Draw control - //-------------------------------------------------------------------- - GuiDrawRectangle(RAYGUI_CLITERAL(Rectangle){ bounds.x, bounds.y, RAYGUI_GROUPBOX_LINE_THICK, bounds.height }, 0, BLANK, GetColor(GuiGetStyle(DEFAULT, (state == STATE_DISABLED)? (int)BORDER_COLOR_DISABLED : (int)LINE_COLOR))); - GuiDrawRectangle(RAYGUI_CLITERAL(Rectangle){ bounds.x, bounds.y + bounds.height - 1, bounds.width, RAYGUI_GROUPBOX_LINE_THICK }, 0, BLANK, GetColor(GuiGetStyle(DEFAULT, (state == STATE_DISABLED)? (int)BORDER_COLOR_DISABLED : (int)LINE_COLOR))); - GuiDrawRectangle(RAYGUI_CLITERAL(Rectangle){ bounds.x + bounds.width - 1, bounds.y, RAYGUI_GROUPBOX_LINE_THICK, bounds.height }, 0, BLANK, GetColor(GuiGetStyle(DEFAULT, (state == STATE_DISABLED)? (int)BORDER_COLOR_DISABLED : (int)LINE_COLOR))); - - GuiLine(RAYGUI_CLITERAL(Rectangle){ bounds.x, bounds.y - GuiGetStyle(DEFAULT, TEXT_SIZE)/2, bounds.width, (float)GuiGetStyle(DEFAULT, TEXT_SIZE) }, text); - //-------------------------------------------------------------------- - - return result; -} - -// Line control -int GuiLine(Rectangle bounds, const char *text) -{ - #if !defined(RAYGUI_LINE_ORIGIN_SIZE) - #define RAYGUI_LINE_MARGIN_TEXT 12 - #endif - #if !defined(RAYGUI_LINE_TEXT_PADDING) - #define RAYGUI_LINE_TEXT_PADDING 4 - #endif - - int result = 0; - GuiState state = guiState; - - Color color = GetColor(GuiGetStyle(DEFAULT, (state == STATE_DISABLED)? (int)BORDER_COLOR_DISABLED : (int)LINE_COLOR)); - - // Draw control - //-------------------------------------------------------------------- - if (text == NULL) GuiDrawRectangle(RAYGUI_CLITERAL(Rectangle){ bounds.x, bounds.y + bounds.height/2, bounds.width, 1 }, 0, BLANK, color); - else - { - Rectangle textBounds = { 0 }; - textBounds.width = (float)GetTextWidth(text) + 2; - textBounds.height = bounds.height; - textBounds.x = bounds.x + RAYGUI_LINE_MARGIN_TEXT; - textBounds.y = bounds.y; - - // Draw line with embedded text label: "--- text --------------" - GuiDrawRectangle(RAYGUI_CLITERAL(Rectangle){ bounds.x, bounds.y + bounds.height/2, RAYGUI_LINE_MARGIN_TEXT - RAYGUI_LINE_TEXT_PADDING, 1 }, 0, BLANK, color); - GuiDrawText(text, textBounds, TEXT_ALIGN_LEFT, color); - GuiDrawRectangle(RAYGUI_CLITERAL(Rectangle){ bounds.x + 12 + textBounds.width + 4, bounds.y + bounds.height/2, bounds.width - textBounds.width - RAYGUI_LINE_MARGIN_TEXT - RAYGUI_LINE_TEXT_PADDING, 1 }, 0, BLANK, color); - } - //-------------------------------------------------------------------- - - return result; -} - -// Panel control -int GuiPanel(Rectangle bounds, const char *text) -{ - #if !defined(RAYGUI_PANEL_BORDER_WIDTH) - #define RAYGUI_PANEL_BORDER_WIDTH 1 - #endif - - int result = 0; - GuiState state = guiState; - - // Text will be drawn as a header bar (if provided) - Rectangle statusBar = { bounds.x, bounds.y, bounds.width, (float)RAYGUI_WINDOWBOX_STATUSBAR_HEIGHT }; - if ((text != NULL) && (bounds.height < RAYGUI_WINDOWBOX_STATUSBAR_HEIGHT*2.0f)) bounds.height = RAYGUI_WINDOWBOX_STATUSBAR_HEIGHT*2.0f; - - if (text != NULL) - { - // Move panel bounds after the header bar - bounds.y += (float)RAYGUI_WINDOWBOX_STATUSBAR_HEIGHT - 1; - bounds.height -= (float)RAYGUI_WINDOWBOX_STATUSBAR_HEIGHT - 1; - } - - // Draw control - //-------------------------------------------------------------------- - if (text != NULL) GuiStatusBar(statusBar, text); // Draw panel header as status bar - - GuiDrawRectangle(bounds, RAYGUI_PANEL_BORDER_WIDTH, GetColor(GuiGetStyle(DEFAULT, (state == STATE_DISABLED)? (int)BORDER_COLOR_DISABLED: (int)LINE_COLOR)), - GetColor(GuiGetStyle(DEFAULT, (state == STATE_DISABLED)? BASE_COLOR_DISABLED : BACKGROUND_COLOR))); - //-------------------------------------------------------------------- - - return result; -} - -// Tab Bar control -// NOTE: Using GuiToggle() for the TABS -int GuiTabBar(Rectangle bounds, const char **text, int count, int *active) -{ - #define RAYGUI_TABBAR_ITEM_WIDTH 160 - - int result = -1; - //GuiState state = guiState; - - Rectangle tabBounds = { bounds.x, bounds.y, RAYGUI_TABBAR_ITEM_WIDTH, bounds.height }; - - if (*active < 0) *active = 0; - else if (*active > count - 1) *active = count - 1; - - int offsetX = 0; // Required in case tabs go out of screen - offsetX = (*active + 2)*RAYGUI_TABBAR_ITEM_WIDTH - GetScreenWidth(); - if (offsetX < 0) offsetX = 0; - - bool toggle = false; // Required for individual toggles - - // Draw control - //-------------------------------------------------------------------- - for (int i = 0; i < count; i++) - { - tabBounds.x = bounds.x + (RAYGUI_TABBAR_ITEM_WIDTH + 4)*i - offsetX; - - if (tabBounds.x < GetScreenWidth()) - { - // Draw tabs as toggle controls - int textAlignment = GuiGetStyle(TOGGLE, TEXT_ALIGNMENT); - int textPadding = GuiGetStyle(TOGGLE, TEXT_PADDING); - GuiSetStyle(TOGGLE, TEXT_ALIGNMENT, TEXT_ALIGN_LEFT); - GuiSetStyle(TOGGLE, TEXT_PADDING, 8); - - if (i == (*active)) - { - toggle = true; - GuiToggle(tabBounds, GuiIconText(12, text[i]), &toggle); - } - else - { - toggle = false; - GuiToggle(tabBounds, GuiIconText(12, text[i]), &toggle); - if (toggle) *active = i; - } - - // Close tab with middle mouse button pressed - if (CheckCollisionPointRec(GetMousePosition(), tabBounds) && IsMouseButtonPressed(MOUSE_MIDDLE_BUTTON)) result = i; - - GuiSetStyle(TOGGLE, TEXT_PADDING, textPadding); - GuiSetStyle(TOGGLE, TEXT_ALIGNMENT, textAlignment); - - // Draw tab close button - // NOTE: Only draw close button for current tab: if (CheckCollisionPointRec(mousePosition, tabBounds)) - int tempBorderWidth = GuiGetStyle(BUTTON, BORDER_WIDTH); - int tempTextAlignment = GuiGetStyle(BUTTON, TEXT_ALIGNMENT); - GuiSetStyle(BUTTON, BORDER_WIDTH, 1); - GuiSetStyle(BUTTON, TEXT_ALIGNMENT, TEXT_ALIGN_CENTER); -#if defined(RAYGUI_NO_ICONS) - if (GuiButton(RAYGUI_CLITERAL(Rectangle){ tabBounds.x + tabBounds.width - 14 - 5, tabBounds.y + 5, 14, 14 }, "x")) result = i; -#else - if (GuiButton(RAYGUI_CLITERAL(Rectangle){ tabBounds.x + tabBounds.width - 14 - 5, tabBounds.y + 5, 14, 14 }, GuiIconText(ICON_CROSS_SMALL, NULL))) result = i; -#endif - GuiSetStyle(BUTTON, BORDER_WIDTH, tempBorderWidth); - GuiSetStyle(BUTTON, TEXT_ALIGNMENT, tempTextAlignment); - } - } - - // Draw tab-bar bottom line - GuiDrawRectangle(RAYGUI_CLITERAL(Rectangle){ bounds.x, bounds.y + bounds.height - 1, bounds.width, 1 }, 0, BLANK, GetColor(GuiGetStyle(TOGGLE, BORDER_COLOR_NORMAL))); - //-------------------------------------------------------------------- - - return result; // Return as result the current TAB closing requested -} - -// Scroll Panel control -int GuiScrollPanel(Rectangle bounds, const char *text, Rectangle content, Vector2 *scroll, Rectangle *view) -{ - #define RAYGUI_MIN_SCROLLBAR_WIDTH 40 - #define RAYGUI_MIN_SCROLLBAR_HEIGHT 40 - #define RAYGUI_MIN_MOUSE_WHEEL_SPEED 20 - - int result = 0; - GuiState state = guiState; - - Rectangle temp = { 0 }; - if (view == NULL) view = &temp; - - Vector2 scrollPos = { 0.0f, 0.0f }; - if (scroll != NULL) scrollPos = *scroll; - - // Text will be drawn as a header bar (if provided) - Rectangle statusBar = { bounds.x, bounds.y, bounds.width, (float)RAYGUI_WINDOWBOX_STATUSBAR_HEIGHT }; - if (bounds.height < RAYGUI_WINDOWBOX_STATUSBAR_HEIGHT*2.0f) bounds.height = RAYGUI_WINDOWBOX_STATUSBAR_HEIGHT*2.0f; - - if (text != NULL) - { - // Move panel bounds after the header bar - bounds.y += (float)RAYGUI_WINDOWBOX_STATUSBAR_HEIGHT - 1; - bounds.height -= (float)RAYGUI_WINDOWBOX_STATUSBAR_HEIGHT + 1; - } - - bool hasHorizontalScrollBar = (content.width > bounds.width - 2*GuiGetStyle(DEFAULT, BORDER_WIDTH))? true : false; - bool hasVerticalScrollBar = (content.height > bounds.height - 2*GuiGetStyle(DEFAULT, BORDER_WIDTH))? true : false; - - // Recheck to account for the other scrollbar being visible - if (!hasHorizontalScrollBar) hasHorizontalScrollBar = (hasVerticalScrollBar && (content.width > (bounds.width - 2*GuiGetStyle(DEFAULT, BORDER_WIDTH) - GuiGetStyle(LISTVIEW, SCROLLBAR_WIDTH))))? true : false; - if (!hasVerticalScrollBar) hasVerticalScrollBar = (hasHorizontalScrollBar && (content.height > (bounds.height - 2*GuiGetStyle(DEFAULT, BORDER_WIDTH) - GuiGetStyle(LISTVIEW, SCROLLBAR_WIDTH))))? true : false; - - int horizontalScrollBarWidth = hasHorizontalScrollBar? GuiGetStyle(LISTVIEW, SCROLLBAR_WIDTH) : 0; - int verticalScrollBarWidth = hasVerticalScrollBar? GuiGetStyle(LISTVIEW, SCROLLBAR_WIDTH) : 0; - Rectangle horizontalScrollBar = { - (float)((GuiGetStyle(LISTVIEW, SCROLLBAR_SIDE) == SCROLLBAR_LEFT_SIDE)? (float)bounds.x + verticalScrollBarWidth : (float)bounds.x) + GuiGetStyle(DEFAULT, BORDER_WIDTH), - (float)bounds.y + bounds.height - horizontalScrollBarWidth - GuiGetStyle(DEFAULT, BORDER_WIDTH), - (float)bounds.width - verticalScrollBarWidth - 2*GuiGetStyle(DEFAULT, BORDER_WIDTH), - (float)horizontalScrollBarWidth - }; - Rectangle verticalScrollBar = { - (float)((GuiGetStyle(LISTVIEW, SCROLLBAR_SIDE) == SCROLLBAR_LEFT_SIDE)? (float)bounds.x + GuiGetStyle(DEFAULT, BORDER_WIDTH) : (float)bounds.x + bounds.width - verticalScrollBarWidth - GuiGetStyle(DEFAULT, BORDER_WIDTH)), - (float)bounds.y + GuiGetStyle(DEFAULT, BORDER_WIDTH), - (float)verticalScrollBarWidth, - (float)bounds.height - horizontalScrollBarWidth - 2*GuiGetStyle(DEFAULT, BORDER_WIDTH) - }; - - // Make sure scroll bars have a minimum width/height - if (horizontalScrollBar.width < RAYGUI_MIN_SCROLLBAR_WIDTH) horizontalScrollBar.width = RAYGUI_MIN_SCROLLBAR_WIDTH; - if (verticalScrollBar.height < RAYGUI_MIN_SCROLLBAR_HEIGHT) verticalScrollBar.height = RAYGUI_MIN_SCROLLBAR_HEIGHT; - - // Calculate view area (area without the scrollbars) - *view = (GuiGetStyle(LISTVIEW, SCROLLBAR_SIDE) == SCROLLBAR_LEFT_SIDE)? - RAYGUI_CLITERAL(Rectangle){ bounds.x + verticalScrollBarWidth + GuiGetStyle(DEFAULT, BORDER_WIDTH), bounds.y + GuiGetStyle(DEFAULT, BORDER_WIDTH), bounds.width - 2*GuiGetStyle(DEFAULT, BORDER_WIDTH) - verticalScrollBarWidth, bounds.height - 2*GuiGetStyle(DEFAULT, BORDER_WIDTH) - horizontalScrollBarWidth } : - RAYGUI_CLITERAL(Rectangle){ bounds.x + GuiGetStyle(DEFAULT, BORDER_WIDTH), bounds.y + GuiGetStyle(DEFAULT, BORDER_WIDTH), bounds.width - 2*GuiGetStyle(DEFAULT, BORDER_WIDTH) - verticalScrollBarWidth, bounds.height - 2*GuiGetStyle(DEFAULT, BORDER_WIDTH) - horizontalScrollBarWidth }; - - // Clip view area to the actual content size - if (view->width > content.width) view->width = content.width; - if (view->height > content.height) view->height = content.height; - - float horizontalMin = hasHorizontalScrollBar? ((GuiGetStyle(LISTVIEW, SCROLLBAR_SIDE) == SCROLLBAR_LEFT_SIDE)? (float)-verticalScrollBarWidth : 0) - (float)GuiGetStyle(DEFAULT, BORDER_WIDTH) : (((float)GuiGetStyle(LISTVIEW, SCROLLBAR_SIDE) == SCROLLBAR_LEFT_SIDE)? (float)-verticalScrollBarWidth : 0) - (float)GuiGetStyle(DEFAULT, BORDER_WIDTH); - float horizontalMax = hasHorizontalScrollBar? content.width - bounds.width + (float)verticalScrollBarWidth + GuiGetStyle(DEFAULT, BORDER_WIDTH) - (((float)GuiGetStyle(LISTVIEW, SCROLLBAR_SIDE) == SCROLLBAR_LEFT_SIDE)? (float)verticalScrollBarWidth : 0) : (float)-GuiGetStyle(DEFAULT, BORDER_WIDTH); - float verticalMin = hasVerticalScrollBar? 0.0f : -1.0f; - float verticalMax = hasVerticalScrollBar? content.height - bounds.height + (float)horizontalScrollBarWidth + (float)GuiGetStyle(DEFAULT, BORDER_WIDTH) : (float)-GuiGetStyle(DEFAULT, BORDER_WIDTH); - - // Update control - //-------------------------------------------------------------------- - if ((state != STATE_DISABLED) && !guiLocked) - { - Vector2 mousePoint = GetMousePosition(); - - // Check button state - if (CheckCollisionPointRec(mousePoint, bounds)) - { - if (IsMouseButtonDown(MOUSE_LEFT_BUTTON)) state = STATE_PRESSED; - else state = STATE_FOCUSED; - -#if defined(SUPPORT_SCROLLBAR_KEY_INPUT) - if (hasHorizontalScrollBar) - { - if (IsKeyDown(KEY_RIGHT)) scrollPos.x -= GuiGetStyle(SCROLLBAR, SCROLL_SPEED); - if (IsKeyDown(KEY_LEFT)) scrollPos.x += GuiGetStyle(SCROLLBAR, SCROLL_SPEED); - } - - if (hasVerticalScrollBar) - { - if (IsKeyDown(KEY_DOWN)) scrollPos.y -= GuiGetStyle(SCROLLBAR, SCROLL_SPEED); - if (IsKeyDown(KEY_UP)) scrollPos.y += GuiGetStyle(SCROLLBAR, SCROLL_SPEED); - } -#endif - float wheelMove = GetMouseWheelMove(); - - // Set scrolling speed with mouse wheel based on ratio between bounds and content - Vector2 mouseWheelSpeed = { content.width/bounds.width, content.height/bounds.height }; - if (mouseWheelSpeed.x < RAYGUI_MIN_MOUSE_WHEEL_SPEED) mouseWheelSpeed.x = RAYGUI_MIN_MOUSE_WHEEL_SPEED; - if (mouseWheelSpeed.y < RAYGUI_MIN_MOUSE_WHEEL_SPEED) mouseWheelSpeed.y = RAYGUI_MIN_MOUSE_WHEEL_SPEED; - - // Horizontal and vertical scrolling with mouse wheel - if (hasHorizontalScrollBar && (IsKeyDown(KEY_LEFT_CONTROL) || IsKeyDown(KEY_LEFT_SHIFT))) scrollPos.x += wheelMove*mouseWheelSpeed.x; - else scrollPos.y += wheelMove*mouseWheelSpeed.y; // Vertical scroll - } - } - - // Normalize scroll values - if (scrollPos.x > -horizontalMin) scrollPos.x = -horizontalMin; - if (scrollPos.x < -horizontalMax) scrollPos.x = -horizontalMax; - if (scrollPos.y > -verticalMin) scrollPos.y = -verticalMin; - if (scrollPos.y < -verticalMax) scrollPos.y = -verticalMax; - //-------------------------------------------------------------------- - - // Draw control - //-------------------------------------------------------------------- - if (text != NULL) GuiStatusBar(statusBar, text); // Draw panel header as status bar - - GuiDrawRectangle(bounds, 0, BLANK, GetColor(GuiGetStyle(DEFAULT, BACKGROUND_COLOR))); // Draw background - - // Save size of the scrollbar slider - const int slider = GuiGetStyle(SCROLLBAR, SCROLL_SLIDER_SIZE); - - // Draw horizontal scrollbar if visible - if (hasHorizontalScrollBar) - { - // Change scrollbar slider size to show the diff in size between the content width and the widget width - GuiSetStyle(SCROLLBAR, SCROLL_SLIDER_SIZE, (int)(((bounds.width - 2*GuiGetStyle(DEFAULT, BORDER_WIDTH) - verticalScrollBarWidth)/(int)content.width)*((int)bounds.width - 2*GuiGetStyle(DEFAULT, BORDER_WIDTH) - verticalScrollBarWidth))); - scrollPos.x = (float)-GuiScrollBar(horizontalScrollBar, (int)-scrollPos.x, (int)horizontalMin, (int)horizontalMax); - } - else scrollPos.x = 0.0f; - - // Draw vertical scrollbar if visible - if (hasVerticalScrollBar) - { - // Change scrollbar slider size to show the diff in size between the content height and the widget height - GuiSetStyle(SCROLLBAR, SCROLL_SLIDER_SIZE, (int)(((bounds.height - 2*GuiGetStyle(DEFAULT, BORDER_WIDTH) - horizontalScrollBarWidth)/(int)content.height)*((int)bounds.height - 2*GuiGetStyle(DEFAULT, BORDER_WIDTH) - horizontalScrollBarWidth))); - scrollPos.y = (float)-GuiScrollBar(verticalScrollBar, (int)-scrollPos.y, (int)verticalMin, (int)verticalMax); - } - else scrollPos.y = 0.0f; - - // Draw detail corner rectangle if both scroll bars are visible - if (hasHorizontalScrollBar && hasVerticalScrollBar) - { - Rectangle corner = { (GuiGetStyle(LISTVIEW, SCROLLBAR_SIDE) == SCROLLBAR_LEFT_SIDE)? (bounds.x + GuiGetStyle(DEFAULT, BORDER_WIDTH) + 2) : (horizontalScrollBar.x + horizontalScrollBar.width + 2), verticalScrollBar.y + verticalScrollBar.height + 2, (float)horizontalScrollBarWidth - 4, (float)verticalScrollBarWidth - 4 }; - GuiDrawRectangle(corner, 0, BLANK, GetColor(GuiGetStyle(LISTVIEW, TEXT + (state*3)))); - } - - // Draw scrollbar lines depending on current state - GuiDrawRectangle(bounds, GuiGetStyle(LISTVIEW, BORDER_WIDTH), GetColor(GuiGetStyle(LISTVIEW, BORDER + (state*3))), BLANK); - - // Set scrollbar slider size back to the way it was before - GuiSetStyle(SCROLLBAR, SCROLL_SLIDER_SIZE, slider); - //-------------------------------------------------------------------- - - if (scroll != NULL) *scroll = scrollPos; - - return result; -} - -// Label control -int GuiLabel(Rectangle bounds, const char *text) -{ - int result = 0; - GuiState state = guiState; - - // Update control - //-------------------------------------------------------------------- - //... - //-------------------------------------------------------------------- - - // Draw control - //-------------------------------------------------------------------- - GuiDrawText(text, GetTextBounds(LABEL, bounds), GuiGetStyle(LABEL, TEXT_ALIGNMENT), GetColor(GuiGetStyle(LABEL, TEXT + (state*3)))); - //-------------------------------------------------------------------- - - return result; -} - -// Button control, returns true when clicked -int GuiButton(Rectangle bounds, const char *text) -{ - int result = 0; - GuiState state = guiState; - - // Update control - //-------------------------------------------------------------------- - if ((state != STATE_DISABLED) && !guiLocked && !guiControlExclusiveMode) - { - Vector2 mousePoint = GetMousePosition(); - - // Check button state - if (CheckCollisionPointRec(mousePoint, bounds)) - { - if (IsMouseButtonDown(MOUSE_LEFT_BUTTON)) state = STATE_PRESSED; - else state = STATE_FOCUSED; - - if (IsMouseButtonReleased(MOUSE_LEFT_BUTTON)) result = 1; - } - } - //-------------------------------------------------------------------- - - // Draw control - //-------------------------------------------------------------------- - GuiDrawRectangle(bounds, GuiGetStyle(BUTTON, BORDER_WIDTH), GetColor(GuiGetStyle(BUTTON, BORDER + (state*3))), GetColor(GuiGetStyle(BUTTON, BASE + (state*3)))); - GuiDrawText(text, GetTextBounds(BUTTON, bounds), GuiGetStyle(BUTTON, TEXT_ALIGNMENT), GetColor(GuiGetStyle(BUTTON, TEXT + (state*3)))); - - if (state == STATE_FOCUSED) GuiTooltip(bounds); - //------------------------------------------------------------------ - - return result; // Button pressed: result = 1 -} - -// Label button control -int GuiLabelButton(Rectangle bounds, const char *text) -{ - GuiState state = guiState; - bool pressed = false; - - // NOTE: We force bounds.width to be all text - float textWidth = (float)GetTextWidth(text); - if ((bounds.width - 2*GuiGetStyle(LABEL, BORDER_WIDTH) - 2*GuiGetStyle(LABEL, TEXT_PADDING)) < textWidth) bounds.width = textWidth + 2*GuiGetStyle(LABEL, BORDER_WIDTH) + 2*GuiGetStyle(LABEL, TEXT_PADDING) + 2; - - // Update control - //-------------------------------------------------------------------- - if ((state != STATE_DISABLED) && !guiLocked && !guiControlExclusiveMode) - { - Vector2 mousePoint = GetMousePosition(); - - // Check checkbox state - if (CheckCollisionPointRec(mousePoint, bounds)) - { - if (IsMouseButtonDown(MOUSE_LEFT_BUTTON)) state = STATE_PRESSED; - else state = STATE_FOCUSED; - - if (IsMouseButtonReleased(MOUSE_LEFT_BUTTON)) pressed = true; - } - } - //-------------------------------------------------------------------- - - // Draw control - //-------------------------------------------------------------------- - GuiDrawText(text, GetTextBounds(LABEL, bounds), GuiGetStyle(LABEL, TEXT_ALIGNMENT), GetColor(GuiGetStyle(LABEL, TEXT + (state*3)))); - //-------------------------------------------------------------------- - - return pressed; -} - -// Toggle Button control -int GuiToggle(Rectangle bounds, const char *text, bool *active) -{ - int result = 0; - GuiState state = guiState; - - bool temp = false; - if (active == NULL) active = &temp; - - // Update control - //-------------------------------------------------------------------- - if ((state != STATE_DISABLED) && !guiLocked && !guiControlExclusiveMode) - { - Vector2 mousePoint = GetMousePosition(); - - // Check toggle button state - if (CheckCollisionPointRec(mousePoint, bounds)) - { - if (IsMouseButtonDown(MOUSE_LEFT_BUTTON)) state = STATE_PRESSED; - else if (IsMouseButtonReleased(MOUSE_LEFT_BUTTON)) - { - state = STATE_NORMAL; - *active = !(*active); - } - else state = STATE_FOCUSED; - } - } - //-------------------------------------------------------------------- - - // Draw control - //-------------------------------------------------------------------- - if (state == STATE_NORMAL) - { - GuiDrawRectangle(bounds, GuiGetStyle(TOGGLE, BORDER_WIDTH), GetColor(GuiGetStyle(TOGGLE, ((*active)? BORDER_COLOR_PRESSED : (BORDER + state*3)))), GetColor(GuiGetStyle(TOGGLE, ((*active)? BASE_COLOR_PRESSED : (BASE + state*3))))); - GuiDrawText(text, GetTextBounds(TOGGLE, bounds), GuiGetStyle(TOGGLE, TEXT_ALIGNMENT), GetColor(GuiGetStyle(TOGGLE, ((*active)? TEXT_COLOR_PRESSED : (TEXT + state*3))))); - } - else - { - GuiDrawRectangle(bounds, GuiGetStyle(TOGGLE, BORDER_WIDTH), GetColor(GuiGetStyle(TOGGLE, BORDER + state*3)), GetColor(GuiGetStyle(TOGGLE, BASE + state*3))); - GuiDrawText(text, GetTextBounds(TOGGLE, bounds), GuiGetStyle(TOGGLE, TEXT_ALIGNMENT), GetColor(GuiGetStyle(TOGGLE, TEXT + state*3))); - } - - if (state == STATE_FOCUSED) GuiTooltip(bounds); - //-------------------------------------------------------------------- - - return result; -} - -// Toggle Group control -int GuiToggleGroup(Rectangle bounds, const char *text, int *active) -{ - #if !defined(RAYGUI_TOGGLEGROUP_MAX_ITEMS) - #define RAYGUI_TOGGLEGROUP_MAX_ITEMS 32 - #endif - - int result = 0; - float initBoundsX = bounds.x; - - int temp = 0; - if (active == NULL) active = &temp; - - bool toggle = false; // Required for individual toggles - - // Get substrings items from text (items pointers) - int rows[RAYGUI_TOGGLEGROUP_MAX_ITEMS] = { 0 }; - int itemCount = 0; - const char **items = GuiTextSplit(text, ';', &itemCount, rows); - - int prevRow = rows[0]; - - for (int i = 0; i < itemCount; i++) - { - if (prevRow != rows[i]) - { - bounds.x = initBoundsX; - bounds.y += (bounds.height + GuiGetStyle(TOGGLE, GROUP_PADDING)); - prevRow = rows[i]; - } - - if (i == (*active)) - { - toggle = true; - GuiToggle(bounds, items[i], &toggle); - } - else - { - toggle = false; - GuiToggle(bounds, items[i], &toggle); - if (toggle) *active = i; - } - - bounds.x += (bounds.width + GuiGetStyle(TOGGLE, GROUP_PADDING)); - } - - return result; -} - -// Toggle Slider control extended -int GuiToggleSlider(Rectangle bounds, const char *text, int *active) -{ - int result = 0; - GuiState state = guiState; - - int temp = 0; - if (active == NULL) active = &temp; - - //bool toggle = false; // Required for individual toggles - - // Get substrings items from text (items pointers) - int itemCount = 0; - const char **items = NULL; - - if (text != NULL) items = GuiTextSplit(text, ';', &itemCount, NULL); - - Rectangle slider = { - 0, // Calculated later depending on the active toggle - bounds.y + GuiGetStyle(SLIDER, BORDER_WIDTH) + GuiGetStyle(SLIDER, SLIDER_PADDING), - (bounds.width - 2*GuiGetStyle(SLIDER, BORDER_WIDTH) - (itemCount + 1)*GuiGetStyle(SLIDER, SLIDER_PADDING))/itemCount, - bounds.height - 2*GuiGetStyle(SLIDER, BORDER_WIDTH) - 2*GuiGetStyle(SLIDER, SLIDER_PADDING) }; - - // Update control - //-------------------------------------------------------------------- - if ((state != STATE_DISABLED) && !guiLocked) - { - Vector2 mousePoint = GetMousePosition(); - - if (CheckCollisionPointRec(mousePoint, bounds)) - { - if (IsMouseButtonDown(MOUSE_LEFT_BUTTON)) state = STATE_PRESSED; - else if (IsMouseButtonReleased(MOUSE_LEFT_BUTTON)) - { - state = STATE_PRESSED; - (*active)++; - result = 1; - } - else state = STATE_FOCUSED; - } - - if ((*active) && (state != STATE_FOCUSED)) state = STATE_PRESSED; - } - - if (*active >= itemCount) *active = 0; - slider.x = bounds.x + GuiGetStyle(SLIDER, BORDER_WIDTH) + (*active + 1)*GuiGetStyle(SLIDER, SLIDER_PADDING) + (*active)*slider.width; - //-------------------------------------------------------------------- - - // Draw control - //-------------------------------------------------------------------- - GuiDrawRectangle(bounds, GuiGetStyle(SLIDER, BORDER_WIDTH), GetColor(GuiGetStyle(TOGGLE, BORDER + (state*3))), - GetColor(GuiGetStyle(TOGGLE, BASE_COLOR_NORMAL))); - - // Draw internal slider - if (state == STATE_NORMAL) GuiDrawRectangle(slider, 0, BLANK, GetColor(GuiGetStyle(SLIDER, BASE_COLOR_PRESSED))); - else if (state == STATE_FOCUSED) GuiDrawRectangle(slider, 0, BLANK, GetColor(GuiGetStyle(SLIDER, BASE_COLOR_FOCUSED))); - else if (state == STATE_PRESSED) GuiDrawRectangle(slider, 0, BLANK, GetColor(GuiGetStyle(SLIDER, BASE_COLOR_PRESSED))); - - // Draw text in slider - if (text != NULL) - { - Rectangle textBounds = { 0 }; - textBounds.width = (float)GetTextWidth(text); - textBounds.height = (float)GuiGetStyle(DEFAULT, TEXT_SIZE); - textBounds.x = slider.x + slider.width/2 - textBounds.width/2; - textBounds.y = bounds.y + bounds.height/2 - GuiGetStyle(DEFAULT, TEXT_SIZE)/2; - - GuiDrawText(items[*active], textBounds, GuiGetStyle(TOGGLE, TEXT_ALIGNMENT), Fade(GetColor(GuiGetStyle(TOGGLE, TEXT + (state*3))), guiAlpha)); - } - //-------------------------------------------------------------------- - - return result; -} - -// Check Box control, returns 1 when state changed -int GuiCheckBox(Rectangle bounds, const char *text, bool *checked) -{ - int result = 0; - GuiState state = guiState; - - bool temp = false; - if (checked == NULL) checked = &temp; - - Rectangle textBounds = { 0 }; - - if (text != NULL) - { - textBounds.width = (float)GetTextWidth(text) + 2; - textBounds.height = (float)GuiGetStyle(DEFAULT, TEXT_SIZE); - textBounds.x = bounds.x + bounds.width + GuiGetStyle(CHECKBOX, TEXT_PADDING); - textBounds.y = bounds.y + bounds.height/2 - GuiGetStyle(DEFAULT, TEXT_SIZE)/2; - if (GuiGetStyle(CHECKBOX, TEXT_ALIGNMENT) == TEXT_ALIGN_LEFT) textBounds.x = bounds.x - textBounds.width - GuiGetStyle(CHECKBOX, TEXT_PADDING); - } - - // Update control - //-------------------------------------------------------------------- - if ((state != STATE_DISABLED) && !guiLocked && !guiControlExclusiveMode) - { - Vector2 mousePoint = GetMousePosition(); - - Rectangle totalBounds = { - (GuiGetStyle(CHECKBOX, TEXT_ALIGNMENT) == TEXT_ALIGN_LEFT)? textBounds.x : bounds.x, - bounds.y, - bounds.width + textBounds.width + GuiGetStyle(CHECKBOX, TEXT_PADDING), - bounds.height, - }; - - // Check checkbox state - if (CheckCollisionPointRec(mousePoint, totalBounds)) - { - if (IsMouseButtonDown(MOUSE_LEFT_BUTTON)) state = STATE_PRESSED; - else state = STATE_FOCUSED; - - if (IsMouseButtonReleased(MOUSE_LEFT_BUTTON)) - { - *checked = !(*checked); - result = 1; - } - } - } - //-------------------------------------------------------------------- - - // Draw control - //-------------------------------------------------------------------- - GuiDrawRectangle(bounds, GuiGetStyle(CHECKBOX, BORDER_WIDTH), GetColor(GuiGetStyle(CHECKBOX, BORDER + (state*3))), BLANK); - - if (*checked) - { - Rectangle check = { bounds.x + GuiGetStyle(CHECKBOX, BORDER_WIDTH) + GuiGetStyle(CHECKBOX, CHECK_PADDING), - bounds.y + GuiGetStyle(CHECKBOX, BORDER_WIDTH) + GuiGetStyle(CHECKBOX, CHECK_PADDING), - bounds.width - 2*(GuiGetStyle(CHECKBOX, BORDER_WIDTH) + GuiGetStyle(CHECKBOX, CHECK_PADDING)), - bounds.height - 2*(GuiGetStyle(CHECKBOX, BORDER_WIDTH) + GuiGetStyle(CHECKBOX, CHECK_PADDING)) }; - GuiDrawRectangle(check, 0, BLANK, GetColor(GuiGetStyle(CHECKBOX, TEXT + state*3))); - } - - GuiDrawText(text, textBounds, (GuiGetStyle(CHECKBOX, TEXT_ALIGNMENT) == TEXT_ALIGN_RIGHT)? TEXT_ALIGN_LEFT : TEXT_ALIGN_RIGHT, GetColor(GuiGetStyle(LABEL, TEXT + (state*3)))); - //-------------------------------------------------------------------- - - return result; -} - -// Combo Box control -int GuiComboBox(Rectangle bounds, const char *text, int *active) -{ - int result = 0; - GuiState state = guiState; - - int temp = 0; - if (active == NULL) active = &temp; - - bounds.width -= (GuiGetStyle(COMBOBOX, COMBO_BUTTON_WIDTH) + GuiGetStyle(COMBOBOX, COMBO_BUTTON_SPACING)); - - Rectangle selector = { (float)bounds.x + bounds.width + GuiGetStyle(COMBOBOX, COMBO_BUTTON_SPACING), - (float)bounds.y, (float)GuiGetStyle(COMBOBOX, COMBO_BUTTON_WIDTH), (float)bounds.height }; - - // Get substrings items from text (items pointers, lengths and count) - int itemCount = 0; - const char **items = GuiTextSplit(text, ';', &itemCount, NULL); - - if (*active < 0) *active = 0; - else if (*active > (itemCount - 1)) *active = itemCount - 1; - - // Update control - //-------------------------------------------------------------------- - if ((state != STATE_DISABLED) && !guiLocked && (itemCount > 1) && !guiControlExclusiveMode) - { - Vector2 mousePoint = GetMousePosition(); - - if (CheckCollisionPointRec(mousePoint, bounds) || - CheckCollisionPointRec(mousePoint, selector)) - { - if (IsMouseButtonPressed(MOUSE_LEFT_BUTTON)) - { - *active += 1; - if (*active >= itemCount) *active = 0; // Cyclic combobox - } - - if (IsMouseButtonDown(MOUSE_LEFT_BUTTON)) state = STATE_PRESSED; - else state = STATE_FOCUSED; - } - } - //-------------------------------------------------------------------- - - // Draw control - //-------------------------------------------------------------------- - // Draw combo box main - GuiDrawRectangle(bounds, GuiGetStyle(COMBOBOX, BORDER_WIDTH), GetColor(GuiGetStyle(COMBOBOX, BORDER + (state*3))), GetColor(GuiGetStyle(COMBOBOX, BASE + (state*3)))); - GuiDrawText(items[*active], GetTextBounds(COMBOBOX, bounds), GuiGetStyle(COMBOBOX, TEXT_ALIGNMENT), GetColor(GuiGetStyle(COMBOBOX, TEXT + (state*3)))); - - // Draw selector using a custom button - // NOTE: BORDER_WIDTH and TEXT_ALIGNMENT forced values - int tempBorderWidth = GuiGetStyle(BUTTON, BORDER_WIDTH); - int tempTextAlign = GuiGetStyle(BUTTON, TEXT_ALIGNMENT); - GuiSetStyle(BUTTON, BORDER_WIDTH, 1); - GuiSetStyle(BUTTON, TEXT_ALIGNMENT, TEXT_ALIGN_CENTER); - - GuiButton(selector, TextFormat("%i/%i", *active + 1, itemCount)); - - GuiSetStyle(BUTTON, TEXT_ALIGNMENT, tempTextAlign); - GuiSetStyle(BUTTON, BORDER_WIDTH, tempBorderWidth); - //-------------------------------------------------------------------- - - return result; -} - -// Dropdown Box control -// NOTE: Returns mouse click -int GuiDropdownBox(Rectangle bounds, const char *text, int *active, bool editMode) -{ - int result = 0; - GuiState state = guiState; - - int temp = 0; - if (active == NULL) active = &temp; - - int itemSelected = *active; - int itemFocused = -1; - - int direction = 0; // Dropdown box open direction: down (default) - if (GuiGetStyle(DROPDOWNBOX, DROPDOWN_ROLL_UP) == 1) direction = 1; // Up - - // Get substrings items from text (items pointers, lengths and count) - int itemCount = 0; - const char **items = GuiTextSplit(text, ';', &itemCount, NULL); - - Rectangle boundsOpen = bounds; - boundsOpen.height = (itemCount + 1)*(bounds.height + GuiGetStyle(DROPDOWNBOX, DROPDOWN_ITEMS_SPACING)); - if (direction == 1) boundsOpen.y -= itemCount*(bounds.height + GuiGetStyle(DROPDOWNBOX, DROPDOWN_ITEMS_SPACING)) + GuiGetStyle(DROPDOWNBOX, DROPDOWN_ITEMS_SPACING); - - Rectangle itemBounds = bounds; - - // Update control - //-------------------------------------------------------------------- - if ((state != STATE_DISABLED) && (editMode || !guiLocked) && (itemCount > 1) && !guiControlExclusiveMode) - { - Vector2 mousePoint = GetMousePosition(); - - if (editMode) - { - state = STATE_PRESSED; - - // Check if mouse has been pressed or released outside limits - if (!CheckCollisionPointRec(mousePoint, boundsOpen)) - { - if (IsMouseButtonPressed(MOUSE_LEFT_BUTTON) || IsMouseButtonReleased(MOUSE_LEFT_BUTTON)) result = 1; - } - - // Check if already selected item has been pressed again - if (CheckCollisionPointRec(mousePoint, bounds) && IsMouseButtonPressed(MOUSE_LEFT_BUTTON)) result = 1; - - // Check focused and selected item - for (int i = 0; i < itemCount; i++) - { - // Update item rectangle y position for next item - if (direction == 0) itemBounds.y += (bounds.height + GuiGetStyle(DROPDOWNBOX, DROPDOWN_ITEMS_SPACING)); - else itemBounds.y -= (bounds.height + GuiGetStyle(DROPDOWNBOX, DROPDOWN_ITEMS_SPACING)); - - if (CheckCollisionPointRec(mousePoint, itemBounds)) - { - itemFocused = i; - if (IsMouseButtonReleased(MOUSE_LEFT_BUTTON)) - { - itemSelected = i; - result = 1; // Item selected - } - break; - } - } - - itemBounds = bounds; - } - else - { - if (CheckCollisionPointRec(mousePoint, bounds)) - { - if (IsMouseButtonPressed(MOUSE_LEFT_BUTTON)) - { - result = 1; - state = STATE_PRESSED; - } - else state = STATE_FOCUSED; - } - } - } - //-------------------------------------------------------------------- - - // Draw control - //-------------------------------------------------------------------- - if (editMode) GuiPanel(boundsOpen, NULL); - - GuiDrawRectangle(bounds, GuiGetStyle(DROPDOWNBOX, BORDER_WIDTH), GetColor(GuiGetStyle(DROPDOWNBOX, BORDER + state*3)), GetColor(GuiGetStyle(DROPDOWNBOX, BASE + state*3))); - GuiDrawText(items[itemSelected], GetTextBounds(DROPDOWNBOX, bounds), GuiGetStyle(DROPDOWNBOX, TEXT_ALIGNMENT), GetColor(GuiGetStyle(DROPDOWNBOX, TEXT + state*3))); - - if (editMode) - { - // Draw visible items - for (int i = 0; i < itemCount; i++) - { - // Update item rectangle y position for next item - if (direction == 0) itemBounds.y += (bounds.height + GuiGetStyle(DROPDOWNBOX, DROPDOWN_ITEMS_SPACING)); - else itemBounds.y -= (bounds.height + GuiGetStyle(DROPDOWNBOX, DROPDOWN_ITEMS_SPACING)); - - if (i == itemSelected) - { - GuiDrawRectangle(itemBounds, GuiGetStyle(DROPDOWNBOX, BORDER_WIDTH), GetColor(GuiGetStyle(DROPDOWNBOX, BORDER_COLOR_PRESSED)), GetColor(GuiGetStyle(DROPDOWNBOX, BASE_COLOR_PRESSED))); - GuiDrawText(items[i], GetTextBounds(DROPDOWNBOX, itemBounds), GuiGetStyle(DROPDOWNBOX, TEXT_ALIGNMENT), GetColor(GuiGetStyle(DROPDOWNBOX, TEXT_COLOR_PRESSED))); - } - else if (i == itemFocused) - { - GuiDrawRectangle(itemBounds, GuiGetStyle(DROPDOWNBOX, BORDER_WIDTH), GetColor(GuiGetStyle(DROPDOWNBOX, BORDER_COLOR_FOCUSED)), GetColor(GuiGetStyle(DROPDOWNBOX, BASE_COLOR_FOCUSED))); - GuiDrawText(items[i], GetTextBounds(DROPDOWNBOX, itemBounds), GuiGetStyle(DROPDOWNBOX, TEXT_ALIGNMENT), GetColor(GuiGetStyle(DROPDOWNBOX, TEXT_COLOR_FOCUSED))); - } - else GuiDrawText(items[i], GetTextBounds(DROPDOWNBOX, itemBounds), GuiGetStyle(DROPDOWNBOX, TEXT_ALIGNMENT), GetColor(GuiGetStyle(DROPDOWNBOX, TEXT_COLOR_NORMAL))); - } - } - - if (!GuiGetStyle(DROPDOWNBOX, DROPDOWN_ARROW_HIDDEN)) - { - // Draw arrows (using icon if available) -#if defined(RAYGUI_NO_ICONS) - GuiDrawText("v", RAYGUI_CLITERAL(Rectangle){ bounds.x + bounds.width - GuiGetStyle(DROPDOWNBOX, ARROW_PADDING), bounds.y + bounds.height/2 - 2, 10, 10 }, - TEXT_ALIGN_CENTER, GetColor(GuiGetStyle(DROPDOWNBOX, TEXT + (state*3)))); -#else - GuiDrawText(direction? "#121#" : "#120#", RAYGUI_CLITERAL(Rectangle){ bounds.x + bounds.width - GuiGetStyle(DROPDOWNBOX, ARROW_PADDING), bounds.y + bounds.height/2 - 6, 10, 10 }, - TEXT_ALIGN_CENTER, GetColor(GuiGetStyle(DROPDOWNBOX, TEXT + (state*3)))); // ICON_ARROW_DOWN_FILL -#endif - } - //-------------------------------------------------------------------- - - *active = itemSelected; - - // TODO: Use result to return more internal states: mouse-press out-of-bounds, mouse-press over selected-item... - return result; // Mouse click: result = 1 -} - -// Text Box control -// NOTE: Returns true on ENTER pressed (useful for data validation) -int GuiTextBox(Rectangle bounds, char *text, int textSize, bool editMode) -{ - #if !defined(RAYGUI_TEXTBOX_AUTO_CURSOR_COOLDOWN) - #define RAYGUI_TEXTBOX_AUTO_CURSOR_COOLDOWN 40 // Frames to wait for autocursor movement - #endif - #if !defined(RAYGUI_TEXTBOX_AUTO_CURSOR_DELAY) - #define RAYGUI_TEXTBOX_AUTO_CURSOR_DELAY 1 // Frames delay for autocursor movement - #endif - - int result = 0; - GuiState state = guiState; - - bool multiline = false; // TODO: Consider multiline text input - int wrapMode = GuiGetStyle(DEFAULT, TEXT_WRAP_MODE); - - Rectangle textBounds = GetTextBounds(TEXTBOX, bounds); - int textLength = (int)strlen(text); // Get current text length - int thisCursorIndex = textBoxCursorIndex; - if (thisCursorIndex > textLength) thisCursorIndex = textLength; - int textWidth = GetTextWidth(text) - GetTextWidth(text + thisCursorIndex); - int textIndexOffset = 0; // Text index offset to start drawing in the box - - // Cursor rectangle - // NOTE: Position X value should be updated - Rectangle cursor = { - textBounds.x + textWidth + GuiGetStyle(DEFAULT, TEXT_SPACING), - textBounds.y + textBounds.height/2 - GuiGetStyle(DEFAULT, TEXT_SIZE), - 2, - (float)GuiGetStyle(DEFAULT, TEXT_SIZE)*2 - }; - - if (cursor.height >= bounds.height) cursor.height = bounds.height - GuiGetStyle(TEXTBOX, BORDER_WIDTH)*2; - if (cursor.y < (bounds.y + GuiGetStyle(TEXTBOX, BORDER_WIDTH))) cursor.y = bounds.y + GuiGetStyle(TEXTBOX, BORDER_WIDTH); - - // Mouse cursor rectangle - // NOTE: Initialized outside of screen - Rectangle mouseCursor = cursor; - mouseCursor.x = -1; - mouseCursor.width = 1; - - // Auto-cursor movement logic - // NOTE: Cursor moves automatically when key down after some time - if (IsKeyDown(KEY_LEFT) || IsKeyDown(KEY_RIGHT) || IsKeyDown(KEY_UP) || IsKeyDown(KEY_DOWN) || IsKeyDown(KEY_BACKSPACE) || IsKeyDown(KEY_DELETE)) autoCursorCooldownCounter++; - else - { - autoCursorCooldownCounter = 0; // GLOBAL: Cursor cooldown counter - autoCursorDelayCounter = 0; // GLOBAL: Cursor delay counter - } - - // Blink-cursor frame counter - //if (!autoCursorMode) blinkCursorFrameCounter++; - //else blinkCursorFrameCounter = 0; - - // Update control - //-------------------------------------------------------------------- - // WARNING: Text editing is only supported under certain conditions: - if ((state != STATE_DISABLED) && // Control not disabled - !GuiGetStyle(TEXTBOX, TEXT_READONLY) && // TextBox not on read-only mode - !guiLocked && // Gui not locked - !guiControlExclusiveMode && // No gui slider on dragging - (wrapMode == TEXT_WRAP_NONE)) // No wrap mode - { - Vector2 mousePosition = GetMousePosition(); - - if (editMode) - { - state = STATE_PRESSED; - - if (textBoxCursorIndex > textLength) textBoxCursorIndex = textLength; - - // If text does not fit in the textbox and current cursor position is out of bounds, - // we add an index offset to text for drawing only what requires depending on cursor - while (textWidth >= textBounds.width) - { - int nextCodepointSize = 0; - GetCodepointNext(text + textIndexOffset, &nextCodepointSize); - - textIndexOffset += nextCodepointSize; - - textWidth = GetTextWidth(text + textIndexOffset) - GetTextWidth(text + textBoxCursorIndex); - } - - int codepoint = GetCharPressed(); // Get Unicode codepoint - if (multiline && IsKeyPressed(KEY_ENTER)) codepoint = (int)'\n'; - - // Encode codepoint as UTF-8 - int codepointSize = 0; - const char *charEncoded = CodepointToUTF8(codepoint, &codepointSize); - - // Add codepoint to text, at current cursor position - // NOTE: Make sure we do not overflow buffer size - if (((multiline && (codepoint == (int)'\n')) || (codepoint >= 32)) && ((textLength + codepointSize) < textSize)) - { - // Move forward data from cursor position - for (int i = (textLength + codepointSize); i > textBoxCursorIndex; i--) text[i] = text[i - codepointSize]; - - // Add new codepoint in current cursor position - for (int i = 0; i < codepointSize; i++) text[textBoxCursorIndex + i] = charEncoded[i]; - - textBoxCursorIndex += codepointSize; - textLength += codepointSize; - - // Make sure text last character is EOL - text[textLength] = '\0'; - } - - // Move cursor to start - if ((textLength > 0) && IsKeyPressed(KEY_HOME)) textBoxCursorIndex = 0; - - // Move cursor to end - if ((textLength > textBoxCursorIndex) && IsKeyPressed(KEY_END)) textBoxCursorIndex = textLength; - - // Delete codepoint from text, after current cursor position - if ((textLength > textBoxCursorIndex) && (IsKeyPressed(KEY_DELETE) || (IsKeyDown(KEY_DELETE) && (autoCursorCooldownCounter >= RAYGUI_TEXTBOX_AUTO_CURSOR_COOLDOWN)))) - { - autoCursorDelayCounter++; - - if (IsKeyPressed(KEY_DELETE) || (autoCursorDelayCounter%RAYGUI_TEXTBOX_AUTO_CURSOR_DELAY) == 0) // Delay every movement some frames - { - int nextCodepointSize = 0; - GetCodepointNext(text + textBoxCursorIndex, &nextCodepointSize); - - // Move backward text from cursor position - for (int i = textBoxCursorIndex; i < textLength; i++) text[i] = text[i + nextCodepointSize]; - - textLength -= codepointSize; - if (textBoxCursorIndex > textLength) textBoxCursorIndex = textLength; - - // Make sure text last character is EOL - text[textLength] = '\0'; - } - } - - // Delete related codepoints from text, before current cursor position - if ((textLength > 0) && IsKeyPressed(KEY_BACKSPACE) && (IsKeyDown(KEY_LEFT_CONTROL) || IsKeyDown(KEY_RIGHT_CONTROL))) - { - int i = textBoxCursorIndex - 1; - int accCodepointSize = 0; - - // Move cursor to the end of word if on space already - while ((i > 0) && isspace(text[i])) - { - int prevCodepointSize = 0; - GetCodepointPrevious(text + i, &prevCodepointSize); - i -= prevCodepointSize; - accCodepointSize += prevCodepointSize; - } - - // Move cursor to the start of the word - while ((i > 0) && !isspace(text[i])) - { - int prevCodepointSize = 0; - GetCodepointPrevious(text + i, &prevCodepointSize); - i -= prevCodepointSize; - accCodepointSize += prevCodepointSize; - } - - // Move forward text from cursor position - for (int j = (textBoxCursorIndex - accCodepointSize); j < textLength; j++) text[j] = text[j + accCodepointSize]; - - // Prevent cursor index from decrementing past 0 - if (textBoxCursorIndex > 0) - { - textBoxCursorIndex -= accCodepointSize; - textLength -= accCodepointSize; - } - - // Make sure text last character is EOL - text[textLength] = '\0'; - } - else if ((textLength > 0) && (IsKeyPressed(KEY_BACKSPACE) || (IsKeyDown(KEY_BACKSPACE) && (autoCursorCooldownCounter >= RAYGUI_TEXTBOX_AUTO_CURSOR_COOLDOWN)))) - { - autoCursorDelayCounter++; - - if (IsKeyPressed(KEY_BACKSPACE) || (autoCursorDelayCounter%RAYGUI_TEXTBOX_AUTO_CURSOR_DELAY) == 0) // Delay every movement some frames - { - int prevCodepointSize = 0; - - // Prevent cursor index from decrementing past 0 - if (textBoxCursorIndex > 0) - { - GetCodepointPrevious(text + textBoxCursorIndex, &prevCodepointSize); - - // Move backward text from cursor position - for (int i = (textBoxCursorIndex - prevCodepointSize); i < textLength; i++) text[i] = text[i + prevCodepointSize]; - - textBoxCursorIndex -= codepointSize; - textLength -= codepointSize; - } - - // Make sure text last character is EOL - text[textLength] = '\0'; - } - } - - // Move cursor position with keys - if (IsKeyPressed(KEY_LEFT) || (IsKeyDown(KEY_LEFT) && (autoCursorCooldownCounter > RAYGUI_TEXTBOX_AUTO_CURSOR_COOLDOWN))) - { - autoCursorDelayCounter++; - - if (IsKeyPressed(KEY_LEFT) || (autoCursorDelayCounter%RAYGUI_TEXTBOX_AUTO_CURSOR_DELAY) == 0) // Delay every movement some frames - { - int prevCodepointSize = 0; - if (textBoxCursorIndex > 0) GetCodepointPrevious(text + textBoxCursorIndex, &prevCodepointSize); - - if (textBoxCursorIndex >= prevCodepointSize) textBoxCursorIndex -= prevCodepointSize; - } - } - else if (IsKeyPressed(KEY_RIGHT) || (IsKeyDown(KEY_RIGHT) && (autoCursorCooldownCounter > RAYGUI_TEXTBOX_AUTO_CURSOR_COOLDOWN))) - { - autoCursorDelayCounter++; - - if (IsKeyPressed(KEY_RIGHT) || (autoCursorDelayCounter%RAYGUI_TEXTBOX_AUTO_CURSOR_DELAY) == 0) // Delay every movement some frames - { - int nextCodepointSize = 0; - GetCodepointNext(text + textBoxCursorIndex, &nextCodepointSize); - - if ((textBoxCursorIndex + nextCodepointSize) <= textLength) textBoxCursorIndex += nextCodepointSize; - } - } - - // Move cursor position with mouse - if (CheckCollisionPointRec(mousePosition, textBounds)) // Mouse hover text - { - float scaleFactor = (float)GuiGetStyle(DEFAULT, TEXT_SIZE)/(float)guiFont.baseSize; - int codepointIndex = 0; - float glyphWidth = 0.0f; - float widthToMouseX = 0; - int mouseCursorIndex = 0; - - for (int i = textIndexOffset; i < textLength; i++) - { - codepoint = GetCodepointNext(&text[i], &codepointSize); - codepointIndex = GetGlyphIndex(guiFont, codepoint); - - if (guiFont.glyphs[codepointIndex].advanceX == 0) glyphWidth = ((float)guiFont.recs[codepointIndex].width*scaleFactor); - else glyphWidth = ((float)guiFont.glyphs[codepointIndex].advanceX*scaleFactor); - - if (mousePosition.x <= (textBounds.x + (widthToMouseX + glyphWidth/2))) - { - mouseCursor.x = textBounds.x + widthToMouseX; - mouseCursorIndex = i; - break; - } - - widthToMouseX += (glyphWidth + (float)GuiGetStyle(DEFAULT, TEXT_SPACING)); - } - - // Check if mouse cursor is at the last position - int textEndWidth = GetTextWidth(text + textIndexOffset); - if (GetMousePosition().x >= (textBounds.x + textEndWidth - glyphWidth/2)) - { - mouseCursor.x = textBounds.x + textEndWidth; - mouseCursorIndex = textLength; - } - - // Place cursor at required index on mouse click - if ((mouseCursor.x >= 0) && IsMouseButtonPressed(MOUSE_LEFT_BUTTON)) - { - cursor.x = mouseCursor.x; - textBoxCursorIndex = mouseCursorIndex; - } - } - else mouseCursor.x = -1; - - // Recalculate cursor position.y depending on textBoxCursorIndex - cursor.x = bounds.x + GuiGetStyle(TEXTBOX, TEXT_PADDING) + GetTextWidth(text + textIndexOffset) - GetTextWidth(text + textBoxCursorIndex) + GuiGetStyle(DEFAULT, TEXT_SPACING); - //if (multiline) cursor.y = GetTextLines() - - // Finish text editing on ENTER or mouse click outside bounds - if ((!multiline && IsKeyPressed(KEY_ENTER)) || - (!CheckCollisionPointRec(mousePosition, bounds) && IsMouseButtonPressed(MOUSE_LEFT_BUTTON))) - { - textBoxCursorIndex = 0; // GLOBAL: Reset the shared cursor index - result = 1; - } - } - else - { - if (CheckCollisionPointRec(mousePosition, bounds)) - { - state = STATE_FOCUSED; - - if (IsMouseButtonPressed(MOUSE_LEFT_BUTTON)) - { - textBoxCursorIndex = textLength; // GLOBAL: Place cursor index to the end of current text - result = 1; - } - } - } - } - //-------------------------------------------------------------------- - - // Draw control - //-------------------------------------------------------------------- - if (state == STATE_PRESSED) - { - GuiDrawRectangle(bounds, GuiGetStyle(TEXTBOX, BORDER_WIDTH), GetColor(GuiGetStyle(TEXTBOX, BORDER + (state*3))), GetColor(GuiGetStyle(TEXTBOX, BASE_COLOR_PRESSED))); - } - else if (state == STATE_DISABLED) - { - GuiDrawRectangle(bounds, GuiGetStyle(TEXTBOX, BORDER_WIDTH), GetColor(GuiGetStyle(TEXTBOX, BORDER + (state*3))), GetColor(GuiGetStyle(TEXTBOX, BASE_COLOR_DISABLED))); - } - else GuiDrawRectangle(bounds, GuiGetStyle(TEXTBOX, BORDER_WIDTH), GetColor(GuiGetStyle(TEXTBOX, BORDER + (state*3))), BLANK); - - // Draw text considering index offset if required - // NOTE: Text index offset depends on cursor position - GuiDrawText(text + textIndexOffset, textBounds, GuiGetStyle(TEXTBOX, TEXT_ALIGNMENT), GetColor(GuiGetStyle(TEXTBOX, TEXT + (state*3)))); - - // Draw cursor - if (editMode && !GuiGetStyle(TEXTBOX, TEXT_READONLY)) - { - //if (autoCursorMode || ((blinkCursorFrameCounter/40)%2 == 0)) - GuiDrawRectangle(cursor, 0, BLANK, GetColor(GuiGetStyle(TEXTBOX, BORDER_COLOR_PRESSED))); - - // Draw mouse position cursor (if required) - if (mouseCursor.x >= 0) GuiDrawRectangle(mouseCursor, 0, BLANK, GetColor(GuiGetStyle(TEXTBOX, BORDER_COLOR_PRESSED))); - } - else if (state == STATE_FOCUSED) GuiTooltip(bounds); - //-------------------------------------------------------------------- - - return result; // Mouse button pressed: result = 1 -} - -/* -// Text Box control with multiple lines and word-wrap -// NOTE: This text-box is readonly, no editing supported by default -bool GuiTextBoxMulti(Rectangle bounds, char *text, int textSize, bool editMode) -{ - bool pressed = false; - - GuiSetStyle(TEXTBOX, TEXT_READONLY, 1); - GuiSetStyle(DEFAULT, TEXT_WRAP_MODE, TEXT_WRAP_WORD); // WARNING: If wrap mode enabled, text editing is not supported - GuiSetStyle(DEFAULT, TEXT_ALIGNMENT_VERTICAL, TEXT_ALIGN_TOP); - - // TODO: Implement methods to calculate cursor position properly - pressed = GuiTextBox(bounds, text, textSize, editMode); - - GuiSetStyle(DEFAULT, TEXT_ALIGNMENT_VERTICAL, TEXT_ALIGN_MIDDLE); - GuiSetStyle(DEFAULT, TEXT_WRAP_MODE, TEXT_WRAP_NONE); - GuiSetStyle(TEXTBOX, TEXT_READONLY, 0); - - return pressed; -} -*/ - -// Spinner control, returns selected value -int GuiSpinner(Rectangle bounds, const char *text, int *value, int minValue, int maxValue, bool editMode) -{ - int result = 1; - GuiState state = guiState; - - int tempValue = *value; - - Rectangle spinner = { bounds.x + GuiGetStyle(SPINNER, SPIN_BUTTON_WIDTH) + GuiGetStyle(SPINNER, SPIN_BUTTON_SPACING), bounds.y, - bounds.width - 2*(GuiGetStyle(SPINNER, SPIN_BUTTON_WIDTH) + GuiGetStyle(SPINNER, SPIN_BUTTON_SPACING)), bounds.height }; - Rectangle leftButtonBound = { (float)bounds.x, (float)bounds.y, (float)GuiGetStyle(SPINNER, SPIN_BUTTON_WIDTH), (float)bounds.height }; - Rectangle rightButtonBound = { (float)bounds.x + bounds.width - GuiGetStyle(SPINNER, SPIN_BUTTON_WIDTH), (float)bounds.y, (float)GuiGetStyle(SPINNER, SPIN_BUTTON_WIDTH), (float)bounds.height }; - - Rectangle textBounds = { 0 }; - if (text != NULL) - { - textBounds.width = (float)GetTextWidth(text) + 2; - textBounds.height = (float)GuiGetStyle(DEFAULT, TEXT_SIZE); - textBounds.x = bounds.x + bounds.width + GuiGetStyle(SPINNER, TEXT_PADDING); - textBounds.y = bounds.y + bounds.height/2 - GuiGetStyle(DEFAULT, TEXT_SIZE)/2; - if (GuiGetStyle(SPINNER, TEXT_ALIGNMENT) == TEXT_ALIGN_LEFT) textBounds.x = bounds.x - textBounds.width - GuiGetStyle(SPINNER, TEXT_PADDING); - } - - // Update control - //-------------------------------------------------------------------- - if ((state != STATE_DISABLED) && !guiLocked && !guiControlExclusiveMode) - { - Vector2 mousePoint = GetMousePosition(); - - // Check spinner state - if (CheckCollisionPointRec(mousePoint, bounds)) - { - if (IsMouseButtonDown(MOUSE_LEFT_BUTTON)) state = STATE_PRESSED; - else state = STATE_FOCUSED; - } - } - -#if defined(RAYGUI_NO_ICONS) - if (GuiButton(leftButtonBound, "<")) tempValue--; - if (GuiButton(rightButtonBound, ">")) tempValue++; -#else - if (GuiButton(leftButtonBound, GuiIconText(ICON_ARROW_LEFT_FILL, NULL))) tempValue--; - if (GuiButton(rightButtonBound, GuiIconText(ICON_ARROW_RIGHT_FILL, NULL))) tempValue++; -#endif - - if (!editMode) - { - if (tempValue < minValue) tempValue = minValue; - if (tempValue > maxValue) tempValue = maxValue; - } - //-------------------------------------------------------------------- - - // Draw control - //-------------------------------------------------------------------- - result = GuiValueBox(spinner, NULL, &tempValue, minValue, maxValue, editMode); - - // Draw value selector custom buttons - // NOTE: BORDER_WIDTH and TEXT_ALIGNMENT forced values - int tempBorderWidth = GuiGetStyle(BUTTON, BORDER_WIDTH); - int tempTextAlign = GuiGetStyle(BUTTON, TEXT_ALIGNMENT); - GuiSetStyle(BUTTON, BORDER_WIDTH, GuiGetStyle(SPINNER, BORDER_WIDTH)); - GuiSetStyle(BUTTON, TEXT_ALIGNMENT, TEXT_ALIGN_CENTER); - - GuiSetStyle(BUTTON, TEXT_ALIGNMENT, tempTextAlign); - GuiSetStyle(BUTTON, BORDER_WIDTH, tempBorderWidth); - - // Draw text label if provided - GuiDrawText(text, textBounds, (GuiGetStyle(SPINNER, TEXT_ALIGNMENT) == TEXT_ALIGN_RIGHT)? TEXT_ALIGN_LEFT : TEXT_ALIGN_RIGHT, GetColor(GuiGetStyle(LABEL, TEXT + (state*3)))); - //-------------------------------------------------------------------- - - *value = tempValue; - return result; -} - -// Value Box control, updates input text with numbers -// NOTE: Requires static variables: frameCounter -int GuiValueBox(Rectangle bounds, const char *text, int *value, int minValue, int maxValue, bool editMode) -{ - #if !defined(RAYGUI_VALUEBOX_MAX_CHARS) - #define RAYGUI_VALUEBOX_MAX_CHARS 32 - #endif - - int result = 0; - GuiState state = guiState; - - char textValue[RAYGUI_VALUEBOX_MAX_CHARS + 1] = "\0"; - sprintf(textValue, "%i", *value); - - Rectangle textBounds = { 0 }; - if (text != NULL) - { - textBounds.width = (float)GetTextWidth(text) + 2; - textBounds.height = (float)GuiGetStyle(DEFAULT, TEXT_SIZE); - textBounds.x = bounds.x + bounds.width + GuiGetStyle(VALUEBOX, TEXT_PADDING); - textBounds.y = bounds.y + bounds.height/2 - GuiGetStyle(DEFAULT, TEXT_SIZE)/2; - if (GuiGetStyle(VALUEBOX, TEXT_ALIGNMENT) == TEXT_ALIGN_LEFT) textBounds.x = bounds.x - textBounds.width - GuiGetStyle(VALUEBOX, TEXT_PADDING); - } - - // Update control - //-------------------------------------------------------------------- - if ((state != STATE_DISABLED) && !guiLocked && !guiControlExclusiveMode) - { - Vector2 mousePoint = GetMousePosition(); - - bool valueHasChanged = false; - - if (editMode) - { - state = STATE_PRESSED; - - int keyCount = (int)strlen(textValue); - - // Only allow keys in range [48..57] - if (keyCount < RAYGUI_VALUEBOX_MAX_CHARS) - { - if (GetTextWidth(textValue) < bounds.width) - { - int key = GetCharPressed(); - if ((key >= 48) && (key <= 57)) - { - textValue[keyCount] = (char)key; - keyCount++; - valueHasChanged = true; - } - } - } - - // Delete text - if (keyCount > 0) - { - if (IsKeyPressed(KEY_BACKSPACE)) - { - keyCount--; - textValue[keyCount] = '\0'; - valueHasChanged = true; - } - } - - if (valueHasChanged) *value = TextToInteger(textValue); - - // NOTE: We are not clamp values until user input finishes - //if (*value > maxValue) *value = maxValue; - //else if (*value < minValue) *value = minValue; - - if ((IsKeyPressed(KEY_ENTER) || IsKeyPressed(KEY_KP_ENTER)) || (!CheckCollisionPointRec(mousePoint, bounds) && IsMouseButtonPressed(MOUSE_LEFT_BUTTON))) - { - if (*value > maxValue) *value = maxValue; - else if (*value < minValue) *value = minValue; - - result = 1; - } - } - else - { - if (*value > maxValue) *value = maxValue; - else if (*value < minValue) *value = minValue; - - if (CheckCollisionPointRec(mousePoint, bounds)) - { - state = STATE_FOCUSED; - if (IsMouseButtonPressed(MOUSE_LEFT_BUTTON)) result = 1; - } - } - } - //-------------------------------------------------------------------- - - // Draw control - //-------------------------------------------------------------------- - Color baseColor = BLANK; - if (state == STATE_PRESSED) baseColor = GetColor(GuiGetStyle(VALUEBOX, BASE_COLOR_PRESSED)); - else if (state == STATE_DISABLED) baseColor = GetColor(GuiGetStyle(VALUEBOX, BASE_COLOR_DISABLED)); - - GuiDrawRectangle(bounds, GuiGetStyle(VALUEBOX, BORDER_WIDTH), GetColor(GuiGetStyle(VALUEBOX, BORDER + (state*3))), baseColor); - GuiDrawText(textValue, GetTextBounds(VALUEBOX, bounds), TEXT_ALIGN_CENTER, GetColor(GuiGetStyle(VALUEBOX, TEXT + (state*3)))); - - // Draw cursor - if (editMode) - { - // NOTE: ValueBox internal text is always centered - Rectangle cursor = { bounds.x + GetTextWidth(textValue)/2 + bounds.width/2 + 1, bounds.y + 2*GuiGetStyle(VALUEBOX, BORDER_WIDTH), 4, bounds.height - 4*GuiGetStyle(VALUEBOX, BORDER_WIDTH) }; - GuiDrawRectangle(cursor, 0, BLANK, GetColor(GuiGetStyle(VALUEBOX, BORDER_COLOR_PRESSED))); - } - - // Draw text label if provided - GuiDrawText(text, textBounds, (GuiGetStyle(VALUEBOX, TEXT_ALIGNMENT) == TEXT_ALIGN_RIGHT)? TEXT_ALIGN_LEFT : TEXT_ALIGN_RIGHT, GetColor(GuiGetStyle(LABEL, TEXT + (state*3)))); - //-------------------------------------------------------------------- - - return result; -} - -// Floating point Value Box control, updates input val_str with numbers -// NOTE: Requires static variables: frameCounter -int GuiValueBoxFloat(Rectangle bounds, const char *text, char *textValue, float *value, bool editMode) -{ - #if !defined(RAYGUI_VALUEBOX_MAX_CHARS) - #define RAYGUI_VALUEBOX_MAX_CHARS 32 - #endif - - int result = 0; - GuiState state = guiState; - - //char textValue[RAYGUI_VALUEBOX_MAX_CHARS + 1] = "\0"; - //sprintf(textValue, "%2.2f", *value); - - Rectangle textBounds = {0}; - if (text != NULL) - { - textBounds.width = (float)GetTextWidth(text) + 2; - textBounds.height = (float)GuiGetStyle(DEFAULT, TEXT_SIZE); - textBounds.x = bounds.x + bounds.width + GuiGetStyle(VALUEBOX, TEXT_PADDING); - textBounds.y = bounds.y + bounds.height/2 - GuiGetStyle(DEFAULT, TEXT_SIZE)/2; - if (GuiGetStyle(VALUEBOX, TEXT_ALIGNMENT) == TEXT_ALIGN_LEFT) textBounds.x = bounds.x - textBounds.width - GuiGetStyle(VALUEBOX, TEXT_PADDING); - } - - // Update control - //-------------------------------------------------------------------- - if ((state != STATE_DISABLED) && !guiLocked && !guiControlExclusiveMode) - { - Vector2 mousePoint = GetMousePosition(); - - bool valueHasChanged = false; - - if (editMode) - { - state = STATE_PRESSED; - - int keyCount = (int)strlen(textValue); - - // Only allow keys in range [48..57] - if (keyCount < RAYGUI_VALUEBOX_MAX_CHARS) - { - if (GetTextWidth(textValue) < bounds.width) - { - int key = GetCharPressed(); - if (((key >= 48) && (key <= 57)) || - (key == '.') || - ((keyCount == 0) && (key == '+')) || // NOTE: Sign can only be in first position - ((keyCount == 0) && (key == '-'))) - { - textValue[keyCount] = (char)key; - keyCount++; - - valueHasChanged = true; - } - } - } - - // Pressed backspace - if (IsKeyPressed(KEY_BACKSPACE)) - { - if (keyCount > 0) - { - keyCount--; - textValue[keyCount] = '\0'; - valueHasChanged = true; - } - } - - if (valueHasChanged) *value = TextToFloat(textValue); - - if ((IsKeyPressed(KEY_ENTER) || IsKeyPressed(KEY_KP_ENTER)) || (!CheckCollisionPointRec(mousePoint, bounds) && IsMouseButtonPressed(MOUSE_LEFT_BUTTON))) result = 1; - } - else - { - if (CheckCollisionPointRec(mousePoint, bounds)) - { - state = STATE_FOCUSED; - if (IsMouseButtonPressed(MOUSE_LEFT_BUTTON)) result = 1; - } - } - } - //-------------------------------------------------------------------- - - // Draw control - //-------------------------------------------------------------------- - Color baseColor = BLANK; - if (state == STATE_PRESSED) baseColor = GetColor(GuiGetStyle(VALUEBOX, BASE_COLOR_PRESSED)); - else if (state == STATE_DISABLED) baseColor = GetColor(GuiGetStyle(VALUEBOX, BASE_COLOR_DISABLED)); - - GuiDrawRectangle(bounds, GuiGetStyle(VALUEBOX, BORDER_WIDTH), GetColor(GuiGetStyle(VALUEBOX, BORDER + (state*3))), baseColor); - GuiDrawText(textValue, GetTextBounds(VALUEBOX, bounds), TEXT_ALIGN_CENTER, GetColor(GuiGetStyle(VALUEBOX, TEXT + (state*3)))); - - // Draw cursor - if (editMode) - { - // NOTE: ValueBox internal text is always centered - Rectangle cursor = {bounds.x + GetTextWidth(textValue)/2 + bounds.width/2 + 1, - bounds.y + 2*GuiGetStyle(VALUEBOX, BORDER_WIDTH), 4, - bounds.height - 4*GuiGetStyle(VALUEBOX, BORDER_WIDTH)}; - GuiDrawRectangle(cursor, 0, BLANK, GetColor(GuiGetStyle(VALUEBOX, BORDER_COLOR_PRESSED))); - } - - // Draw text label if provided - GuiDrawText(text, textBounds, - (GuiGetStyle(VALUEBOX, TEXT_ALIGNMENT) == TEXT_ALIGN_RIGHT)? TEXT_ALIGN_LEFT : TEXT_ALIGN_RIGHT, - GetColor(GuiGetStyle(LABEL, TEXT + (state*3)))); - //-------------------------------------------------------------------- - - return result; -} - -// Slider control with pro parameters -// NOTE: Other GuiSlider*() controls use this one -int GuiSliderPro(Rectangle bounds, const char *textLeft, const char *textRight, float *value, float minValue, float maxValue, int sliderWidth) -{ - int result = 0; - GuiState state = guiState; - - float temp = (maxValue - minValue)/2.0f; - if (value == NULL) value = &temp; - float oldValue = *value; - - Rectangle slider = { bounds.x, bounds.y + GuiGetStyle(SLIDER, BORDER_WIDTH) + GuiGetStyle(SLIDER, SLIDER_PADDING), - 0, bounds.height - 2*GuiGetStyle(SLIDER, BORDER_WIDTH) - 2*GuiGetStyle(SLIDER, SLIDER_PADDING) }; - - // Update control - //-------------------------------------------------------------------- - if ((state != STATE_DISABLED) && !guiLocked) - { - Vector2 mousePoint = GetMousePosition(); - - if (guiControlExclusiveMode) // Allows to keep dragging outside of bounds - { - if (IsMouseButtonDown(MOUSE_LEFT_BUTTON)) - { - if (CHECK_BOUNDS_ID(bounds, guiControlExclusiveRec)) - { - state = STATE_PRESSED; - // Get equivalent value and slider position from mousePosition.x - *value = (maxValue - minValue)*((mousePoint.x - bounds.x - sliderWidth/2)/(bounds.width-sliderWidth)) + minValue; - } - } - else - { - guiControlExclusiveMode = false; - guiControlExclusiveRec = RAYGUI_CLITERAL(Rectangle){ 0, 0, 0, 0 }; - } - } - else if (CheckCollisionPointRec(mousePoint, bounds)) - { - if (IsMouseButtonDown(MOUSE_LEFT_BUTTON)) - { - state = STATE_PRESSED; - guiControlExclusiveMode = true; - guiControlExclusiveRec = bounds; // Store bounds as an identifier when dragging starts - - if (!CheckCollisionPointRec(mousePoint, slider)) - { - // Get equivalent value and slider position from mousePosition.x - *value = (maxValue - minValue)*((mousePoint.x - bounds.x - sliderWidth/2)/(bounds.width-sliderWidth)) + minValue; - } - } - else state = STATE_FOCUSED; - } - - if (*value > maxValue) *value = maxValue; - else if (*value < minValue) *value = minValue; - } - - // Control value change check - if (oldValue == *value) result = 0; - else result = 1; - - // Slider bar limits check - float sliderValue = (((*value - minValue)/(maxValue - minValue))*(bounds.width - sliderWidth - 2*GuiGetStyle(SLIDER, BORDER_WIDTH))); - if (sliderWidth > 0) // Slider - { - slider.x += sliderValue; - slider.width = (float)sliderWidth; - if (slider.x <= (bounds.x + GuiGetStyle(SLIDER, BORDER_WIDTH))) slider.x = bounds.x + GuiGetStyle(SLIDER, BORDER_WIDTH); - else if ((slider.x + slider.width) >= (bounds.x + bounds.width)) slider.x = bounds.x + bounds.width - slider.width - GuiGetStyle(SLIDER, BORDER_WIDTH); - } - else if (sliderWidth == 0) // SliderBar - { - slider.x += GuiGetStyle(SLIDER, BORDER_WIDTH); - slider.width = sliderValue; - if (slider.width > bounds.width) slider.width = bounds.width - 2*GuiGetStyle(SLIDER, BORDER_WIDTH); - } - //-------------------------------------------------------------------- - - // Draw control - //-------------------------------------------------------------------- - GuiDrawRectangle(bounds, GuiGetStyle(SLIDER, BORDER_WIDTH), GetColor(GuiGetStyle(SLIDER, BORDER + (state*3))), GetColor(GuiGetStyle(SLIDER, (state != STATE_DISABLED)? BASE_COLOR_NORMAL : BASE_COLOR_DISABLED))); - - // Draw slider internal bar (depends on state) - if (state == STATE_NORMAL) GuiDrawRectangle(slider, 0, BLANK, GetColor(GuiGetStyle(SLIDER, BASE_COLOR_PRESSED))); - else if (state == STATE_FOCUSED) GuiDrawRectangle(slider, 0, BLANK, GetColor(GuiGetStyle(SLIDER, TEXT_COLOR_FOCUSED))); - else if (state == STATE_PRESSED) GuiDrawRectangle(slider, 0, BLANK, GetColor(GuiGetStyle(SLIDER, TEXT_COLOR_PRESSED))); - - // Draw left/right text if provided - if (textLeft != NULL) - { - Rectangle textBounds = { 0 }; - textBounds.width = (float)GetTextWidth(textLeft); - textBounds.height = (float)GuiGetStyle(DEFAULT, TEXT_SIZE); - textBounds.x = bounds.x - textBounds.width - GuiGetStyle(SLIDER, TEXT_PADDING); - textBounds.y = bounds.y + bounds.height/2 - GuiGetStyle(DEFAULT, TEXT_SIZE)/2; - - GuiDrawText(textLeft, textBounds, TEXT_ALIGN_RIGHT, GetColor(GuiGetStyle(SLIDER, TEXT + (state*3)))); - } - - if (textRight != NULL) - { - Rectangle textBounds = { 0 }; - textBounds.width = (float)GetTextWidth(textRight); - textBounds.height = (float)GuiGetStyle(DEFAULT, TEXT_SIZE); - textBounds.x = bounds.x + bounds.width + GuiGetStyle(SLIDER, TEXT_PADDING); - textBounds.y = bounds.y + bounds.height/2 - GuiGetStyle(DEFAULT, TEXT_SIZE)/2; - - GuiDrawText(textRight, textBounds, TEXT_ALIGN_LEFT, GetColor(GuiGetStyle(SLIDER, TEXT + (state*3)))); - } - //-------------------------------------------------------------------- - - return result; -} - -// Slider control extended, returns selected value and has text -int GuiSlider(Rectangle bounds, const char *textLeft, const char *textRight, float *value, float minValue, float maxValue) -{ - return GuiSliderPro(bounds, textLeft, textRight, value, minValue, maxValue, GuiGetStyle(SLIDER, SLIDER_WIDTH)); -} - -// Slider Bar control extended, returns selected value -int GuiSliderBar(Rectangle bounds, const char *textLeft, const char *textRight, float *value, float minValue, float maxValue) -{ - return GuiSliderPro(bounds, textLeft, textRight, value, minValue, maxValue, 0); -} - -// Progress Bar control extended, shows current progress value -int GuiProgressBar(Rectangle bounds, const char *textLeft, const char *textRight, float *value, float minValue, float maxValue) -{ - int result = 0; - GuiState state = guiState; - - float temp = (maxValue - minValue)/2.0f; - if (value == NULL) value = &temp; - - // Progress bar - Rectangle progress = { bounds.x + GuiGetStyle(PROGRESSBAR, BORDER_WIDTH), - bounds.y + GuiGetStyle(PROGRESSBAR, BORDER_WIDTH) + GuiGetStyle(PROGRESSBAR, PROGRESS_PADDING), 0, - bounds.height - 2*GuiGetStyle(PROGRESSBAR, BORDER_WIDTH) - 2*GuiGetStyle(PROGRESSBAR, PROGRESS_PADDING) }; - - // Update control - //-------------------------------------------------------------------- - if (*value > maxValue) *value = maxValue; - - // WARNING: Working with floats could lead to rounding issues - if ((state != STATE_DISABLED)) progress.width = (float)(*value/(maxValue - minValue))*bounds.width - ((*value >= maxValue)? (float)(2*GuiGetStyle(PROGRESSBAR, BORDER_WIDTH)) : 0.0f); - //-------------------------------------------------------------------- - - // Draw control - //-------------------------------------------------------------------- - if (state == STATE_DISABLED) - { - GuiDrawRectangle(bounds, GuiGetStyle(PROGRESSBAR, BORDER_WIDTH), GetColor(GuiGetStyle(PROGRESSBAR, BORDER + (state*3))), BLANK); - } - else - { - if (*value > minValue) - { - // Draw progress bar with colored border, more visual - GuiDrawRectangle(RAYGUI_CLITERAL(Rectangle){ bounds.x, bounds.y, (int)progress.width + (float)GuiGetStyle(PROGRESSBAR, BORDER_WIDTH), (float)GuiGetStyle(PROGRESSBAR, BORDER_WIDTH) }, 0, BLANK, GetColor(GuiGetStyle(PROGRESSBAR, BORDER_COLOR_FOCUSED))); - GuiDrawRectangle(RAYGUI_CLITERAL(Rectangle){ bounds.x, bounds.y + 1, (float)GuiGetStyle(PROGRESSBAR, BORDER_WIDTH), bounds.height - 2 }, 0, BLANK, GetColor(GuiGetStyle(PROGRESSBAR, BORDER_COLOR_FOCUSED))); - GuiDrawRectangle(RAYGUI_CLITERAL(Rectangle){ bounds.x, bounds.y + bounds.height - 1, (int)progress.width + (float)GuiGetStyle(PROGRESSBAR, BORDER_WIDTH), (float)GuiGetStyle(PROGRESSBAR, BORDER_WIDTH) }, 0, BLANK, GetColor(GuiGetStyle(PROGRESSBAR, BORDER_COLOR_FOCUSED))); - } - else GuiDrawRectangle(RAYGUI_CLITERAL(Rectangle){ bounds.x, bounds.y, (float)GuiGetStyle(PROGRESSBAR, BORDER_WIDTH), bounds.height }, 0, BLANK, GetColor(GuiGetStyle(PROGRESSBAR, BORDER_COLOR_NORMAL))); - - if (*value >= maxValue) GuiDrawRectangle(RAYGUI_CLITERAL(Rectangle){ bounds.x + progress.width + 1, bounds.y, (float)GuiGetStyle(PROGRESSBAR, BORDER_WIDTH), bounds.height }, 0, BLANK, GetColor(GuiGetStyle(PROGRESSBAR, BORDER_COLOR_FOCUSED))); - else - { - // Draw borders not yet reached by value - GuiDrawRectangle(RAYGUI_CLITERAL(Rectangle){ bounds.x + (int)progress.width + 1, bounds.y, bounds.width - (int)progress.width - 1, (float)GuiGetStyle(PROGRESSBAR, BORDER_WIDTH) }, 0, BLANK, GetColor(GuiGetStyle(PROGRESSBAR, BORDER_COLOR_NORMAL))); - GuiDrawRectangle(RAYGUI_CLITERAL(Rectangle){ bounds.x + (int)progress.width + 1, bounds.y + bounds.height - 1, bounds.width - (int)progress.width - 1, (float)GuiGetStyle(PROGRESSBAR, BORDER_WIDTH) }, 0, BLANK, GetColor(GuiGetStyle(PROGRESSBAR, BORDER_COLOR_NORMAL))); - GuiDrawRectangle(RAYGUI_CLITERAL(Rectangle){ bounds.x + bounds.width - 1, bounds.y + 1, (float)GuiGetStyle(PROGRESSBAR, BORDER_WIDTH), bounds.height - 2 }, 0, BLANK, GetColor(GuiGetStyle(PROGRESSBAR, BORDER_COLOR_NORMAL))); - } - - // Draw slider internal progress bar (depends on state) - GuiDrawRectangle(progress, 0, BLANK, GetColor(GuiGetStyle(PROGRESSBAR, BASE_COLOR_PRESSED))); - } - - // Draw left/right text if provided - if (textLeft != NULL) - { - Rectangle textBounds = { 0 }; - textBounds.width = (float)GetTextWidth(textLeft); - textBounds.height = (float)GuiGetStyle(DEFAULT, TEXT_SIZE); - textBounds.x = bounds.x - textBounds.width - GuiGetStyle(PROGRESSBAR, TEXT_PADDING); - textBounds.y = bounds.y + bounds.height/2 - GuiGetStyle(DEFAULT, TEXT_SIZE)/2; - - GuiDrawText(textLeft, textBounds, TEXT_ALIGN_RIGHT, GetColor(GuiGetStyle(PROGRESSBAR, TEXT + (state*3)))); - } - - if (textRight != NULL) - { - Rectangle textBounds = { 0 }; - textBounds.width = (float)GetTextWidth(textRight); - textBounds.height = (float)GuiGetStyle(DEFAULT, TEXT_SIZE); - textBounds.x = bounds.x + bounds.width + GuiGetStyle(PROGRESSBAR, TEXT_PADDING); - textBounds.y = bounds.y + bounds.height/2 - GuiGetStyle(DEFAULT, TEXT_SIZE)/2; - - GuiDrawText(textRight, textBounds, TEXT_ALIGN_LEFT, GetColor(GuiGetStyle(PROGRESSBAR, TEXT + (state*3)))); - } - //-------------------------------------------------------------------- - - return result; -} - -// Status Bar control -int GuiStatusBar(Rectangle bounds, const char *text) -{ - int result = 0; - GuiState state = guiState; - - // Draw control - //-------------------------------------------------------------------- - GuiDrawRectangle(bounds, GuiGetStyle(STATUSBAR, BORDER_WIDTH), GetColor(GuiGetStyle(STATUSBAR, BORDER + (state*3))), GetColor(GuiGetStyle(STATUSBAR, BASE + (state*3)))); - GuiDrawText(text, GetTextBounds(STATUSBAR, bounds), GuiGetStyle(STATUSBAR, TEXT_ALIGNMENT), GetColor(GuiGetStyle(STATUSBAR, TEXT + (state*3)))); - //-------------------------------------------------------------------- - - return result; -} - -// Dummy rectangle control, intended for placeholding -int GuiDummyRec(Rectangle bounds, const char *text) -{ - int result = 0; - GuiState state = guiState; - - // Update control - //-------------------------------------------------------------------- - if ((state != STATE_DISABLED) && !guiLocked && !guiControlExclusiveMode) - { - Vector2 mousePoint = GetMousePosition(); - - // Check button state - if (CheckCollisionPointRec(mousePoint, bounds)) - { - if (IsMouseButtonDown(MOUSE_LEFT_BUTTON)) state = STATE_PRESSED; - else state = STATE_FOCUSED; - } - } - //-------------------------------------------------------------------- - - // Draw control - //-------------------------------------------------------------------- - GuiDrawRectangle(bounds, 0, BLANK, GetColor(GuiGetStyle(DEFAULT, (state != STATE_DISABLED)? BASE_COLOR_NORMAL : BASE_COLOR_DISABLED))); - GuiDrawText(text, GetTextBounds(DEFAULT, bounds), TEXT_ALIGN_CENTER, GetColor(GuiGetStyle(BUTTON, (state != STATE_DISABLED)? TEXT_COLOR_NORMAL : TEXT_COLOR_DISABLED))); - //------------------------------------------------------------------ - - return result; -} - -// List View control -int GuiListView(Rectangle bounds, const char *text, int *scrollIndex, int *active) -{ - int result = 0; - int itemCount = 0; - const char **items = NULL; - - if (text != NULL) items = GuiTextSplit(text, ';', &itemCount, NULL); - - result = GuiListViewEx(bounds, items, itemCount, scrollIndex, active, NULL); - - return result; -} - -// List View control with extended parameters -int GuiListViewEx(Rectangle bounds, const char **text, int count, int *scrollIndex, int *active, int *focus) -{ - int result = 0; - GuiState state = guiState; - - int itemFocused = (focus == NULL)? -1 : *focus; - int itemSelected = (active == NULL)? -1 : *active; - - // Check if we need a scroll bar - bool useScrollBar = false; - if ((GuiGetStyle(LISTVIEW, LIST_ITEMS_HEIGHT) + GuiGetStyle(LISTVIEW, LIST_ITEMS_SPACING))*count > bounds.height) useScrollBar = true; - - // Define base item rectangle [0] - Rectangle itemBounds = { 0 }; - itemBounds.x = bounds.x + GuiGetStyle(LISTVIEW, LIST_ITEMS_SPACING); - itemBounds.y = bounds.y + GuiGetStyle(LISTVIEW, LIST_ITEMS_SPACING) + GuiGetStyle(DEFAULT, BORDER_WIDTH); - itemBounds.width = bounds.width - 2*GuiGetStyle(LISTVIEW, LIST_ITEMS_SPACING) - GuiGetStyle(DEFAULT, BORDER_WIDTH); - itemBounds.height = (float)GuiGetStyle(LISTVIEW, LIST_ITEMS_HEIGHT); - if (useScrollBar) itemBounds.width -= GuiGetStyle(LISTVIEW, SCROLLBAR_WIDTH); - - // Get items on the list - int visibleItems = (int)bounds.height/(GuiGetStyle(LISTVIEW, LIST_ITEMS_HEIGHT) + GuiGetStyle(LISTVIEW, LIST_ITEMS_SPACING)); - if (visibleItems > count) visibleItems = count; - - int startIndex = (scrollIndex == NULL)? 0 : *scrollIndex; - if ((startIndex < 0) || (startIndex > (count - visibleItems))) startIndex = 0; - int endIndex = startIndex + visibleItems; - - // Update control - //-------------------------------------------------------------------- - if ((state != STATE_DISABLED) && !guiLocked && !guiControlExclusiveMode) - { - Vector2 mousePoint = GetMousePosition(); - - // Check mouse inside list view - if (CheckCollisionPointRec(mousePoint, bounds)) - { - state = STATE_FOCUSED; - - // Check focused and selected item - for (int i = 0; i < visibleItems; i++) - { - if (CheckCollisionPointRec(mousePoint, itemBounds)) - { - itemFocused = startIndex + i; - if (IsMouseButtonPressed(MOUSE_LEFT_BUTTON)) - { - if (itemSelected == (startIndex + i)) itemSelected = -1; - else itemSelected = startIndex + i; - } - break; - } - - // Update item rectangle y position for next item - itemBounds.y += (GuiGetStyle(LISTVIEW, LIST_ITEMS_HEIGHT) + GuiGetStyle(LISTVIEW, LIST_ITEMS_SPACING)); - } - - if (useScrollBar) - { - int wheelMove = (int)GetMouseWheelMove(); - startIndex -= wheelMove; - - if (startIndex < 0) startIndex = 0; - else if (startIndex > (count - visibleItems)) startIndex = count - visibleItems; - - endIndex = startIndex + visibleItems; - if (endIndex > count) endIndex = count; - } - } - else itemFocused = -1; - - // Reset item rectangle y to [0] - itemBounds.y = bounds.y + GuiGetStyle(LISTVIEW, LIST_ITEMS_SPACING) + GuiGetStyle(DEFAULT, BORDER_WIDTH); - } - //-------------------------------------------------------------------- - - // Draw control - //-------------------------------------------------------------------- - GuiDrawRectangle(bounds, GuiGetStyle(LISTVIEW, BORDER_WIDTH), GetColor(GuiGetStyle(LISTVIEW, BORDER + state*3)), GetColor(GuiGetStyle(DEFAULT, BACKGROUND_COLOR))); // Draw background - - // Draw visible items - for (int i = 0; ((i < visibleItems) && (text != NULL)); i++) - { - GuiDrawRectangle(itemBounds, GuiGetStyle(LISTVIEW, LIST_ITEMS_BORDER_WIDTH), GetColor(GuiGetStyle(LISTVIEW, BORDER_COLOR_NORMAL)), BLANK); - - if (state == STATE_DISABLED) - { - if ((startIndex + i) == itemSelected) GuiDrawRectangle(itemBounds, GuiGetStyle(LISTVIEW, BORDER_WIDTH), GetColor(GuiGetStyle(LISTVIEW, BORDER_COLOR_DISABLED)), GetColor(GuiGetStyle(LISTVIEW, BASE_COLOR_DISABLED))); - - GuiDrawText(text[startIndex + i], GetTextBounds(DEFAULT, itemBounds), GuiGetStyle(LISTVIEW, TEXT_ALIGNMENT), GetColor(GuiGetStyle(LISTVIEW, TEXT_COLOR_DISABLED))); - } - else - { - if (((startIndex + i) == itemSelected) && (active != NULL)) - { - // Draw item selected - GuiDrawRectangle(itemBounds, GuiGetStyle(LISTVIEW, BORDER_WIDTH), GetColor(GuiGetStyle(LISTVIEW, BORDER_COLOR_PRESSED)), GetColor(GuiGetStyle(LISTVIEW, BASE_COLOR_PRESSED))); - GuiDrawText(text[startIndex + i], GetTextBounds(DEFAULT, itemBounds), GuiGetStyle(LISTVIEW, TEXT_ALIGNMENT), GetColor(GuiGetStyle(LISTVIEW, TEXT_COLOR_PRESSED))); - } - else if (((startIndex + i) == itemFocused)) // && (focus != NULL)) // NOTE: We want items focused, despite not returned! - { - // Draw item focused - GuiDrawRectangle(itemBounds, GuiGetStyle(LISTVIEW, BORDER_WIDTH), GetColor(GuiGetStyle(LISTVIEW, BORDER_COLOR_FOCUSED)), GetColor(GuiGetStyle(LISTVIEW, BASE_COLOR_FOCUSED))); - GuiDrawText(text[startIndex + i], GetTextBounds(DEFAULT, itemBounds), GuiGetStyle(LISTVIEW, TEXT_ALIGNMENT), GetColor(GuiGetStyle(LISTVIEW, TEXT_COLOR_FOCUSED))); - } - else - { - // Draw item normal - GuiDrawText(text[startIndex + i], GetTextBounds(DEFAULT, itemBounds), GuiGetStyle(LISTVIEW, TEXT_ALIGNMENT), GetColor(GuiGetStyle(LISTVIEW, TEXT_COLOR_NORMAL))); - } - } - - // Update item rectangle y position for next item - itemBounds.y += (GuiGetStyle(LISTVIEW, LIST_ITEMS_HEIGHT) + GuiGetStyle(LISTVIEW, LIST_ITEMS_SPACING)); - } - - if (useScrollBar) - { - Rectangle scrollBarBounds = { - bounds.x + bounds.width - GuiGetStyle(LISTVIEW, BORDER_WIDTH) - GuiGetStyle(LISTVIEW, SCROLLBAR_WIDTH), - bounds.y + GuiGetStyle(LISTVIEW, BORDER_WIDTH), (float)GuiGetStyle(LISTVIEW, SCROLLBAR_WIDTH), - bounds.height - 2*GuiGetStyle(DEFAULT, BORDER_WIDTH) - }; - - // Calculate percentage of visible items and apply same percentage to scrollbar - float percentVisible = (float)(endIndex - startIndex)/count; - float sliderSize = bounds.height*percentVisible; - - int prevSliderSize = GuiGetStyle(SCROLLBAR, SCROLL_SLIDER_SIZE); // Save default slider size - int prevScrollSpeed = GuiGetStyle(SCROLLBAR, SCROLL_SPEED); // Save default scroll speed - GuiSetStyle(SCROLLBAR, SCROLL_SLIDER_SIZE, (int)sliderSize); // Change slider size - GuiSetStyle(SCROLLBAR, SCROLL_SPEED, count - visibleItems); // Change scroll speed - - startIndex = GuiScrollBar(scrollBarBounds, startIndex, 0, count - visibleItems); - - GuiSetStyle(SCROLLBAR, SCROLL_SPEED, prevScrollSpeed); // Reset scroll speed to default - GuiSetStyle(SCROLLBAR, SCROLL_SLIDER_SIZE, prevSliderSize); // Reset slider size to default - } - //-------------------------------------------------------------------- - - if (active != NULL) *active = itemSelected; - if (focus != NULL) *focus = itemFocused; - if (scrollIndex != NULL) *scrollIndex = startIndex; - - return result; -} - -// Color Panel control - Color (RGBA) variant. -int GuiColorPanel(Rectangle bounds, const char *text, Color *color) -{ - int result = 0; - - Vector3 vcolor = { (float)color->r/255.0f, (float)color->g/255.0f, (float)color->b/255.0f }; - Vector3 hsv = ConvertRGBtoHSV(vcolor); - Vector3 prevHsv = hsv; // workaround to see if GuiColorPanelHSV modifies the hsv. - - GuiColorPanelHSV(bounds, text, &hsv); - - // Check if the hsv was changed, only then change the color. - // This is required, because the Color->HSV->Color conversion has precision errors. - // Thus the assignment from HSV to Color should only be made, if the HSV has a new user-entered value. - // Otherwise GuiColorPanel would often modify it's color without user input. - // TODO: GuiColorPanelHSV could return 1 if the slider was dragged, to simplify this check. - if (hsv.x != prevHsv.x || hsv.y != prevHsv.y || hsv.z != prevHsv.z) - { - Vector3 rgb = ConvertHSVtoRGB(hsv); - - // NOTE: Vector3ToColor() only available on raylib 1.8.1 - *color = RAYGUI_CLITERAL(Color){ (unsigned char)(255.0f*rgb.x), - (unsigned char)(255.0f*rgb.y), - (unsigned char)(255.0f*rgb.z), - color->a }; - } - return result; -} - -// Color Bar Alpha control -// NOTE: Returns alpha value normalized [0..1] -int GuiColorBarAlpha(Rectangle bounds, const char *text, float *alpha) -{ - #if !defined(RAYGUI_COLORBARALPHA_CHECKED_SIZE) - #define RAYGUI_COLORBARALPHA_CHECKED_SIZE 10 - #endif - - int result = 0; - GuiState state = guiState; - Rectangle selector = { (float)bounds.x + (*alpha)*bounds.width - GuiGetStyle(COLORPICKER, HUEBAR_SELECTOR_HEIGHT)/2, (float)bounds.y - GuiGetStyle(COLORPICKER, HUEBAR_SELECTOR_OVERFLOW), (float)GuiGetStyle(COLORPICKER, HUEBAR_SELECTOR_HEIGHT), (float)bounds.height + GuiGetStyle(COLORPICKER, HUEBAR_SELECTOR_OVERFLOW)*2 }; - - // Update control - //-------------------------------------------------------------------- - if ((state != STATE_DISABLED) && !guiLocked) - { - Vector2 mousePoint = GetMousePosition(); - - if (guiControlExclusiveMode) // Allows to keep dragging outside of bounds - { - if (IsMouseButtonDown(MOUSE_LEFT_BUTTON)) - { - if (CHECK_BOUNDS_ID(bounds, guiControlExclusiveRec)) - { - state = STATE_PRESSED; - - *alpha = (mousePoint.x - bounds.x)/bounds.width; - if (*alpha <= 0.0f) *alpha = 0.0f; - if (*alpha >= 1.0f) *alpha = 1.0f; - } - } - else - { - guiControlExclusiveMode = false; - guiControlExclusiveRec = RAYGUI_CLITERAL(Rectangle){ 0, 0, 0, 0 }; - } - } - else if (CheckCollisionPointRec(mousePoint, bounds) || CheckCollisionPointRec(mousePoint, selector)) - { - if (IsMouseButtonDown(MOUSE_LEFT_BUTTON)) - { - state = STATE_PRESSED; - guiControlExclusiveMode = true; - guiControlExclusiveRec = bounds; // Store bounds as an identifier when dragging starts - - *alpha = (mousePoint.x - bounds.x)/bounds.width; - if (*alpha <= 0.0f) *alpha = 0.0f; - if (*alpha >= 1.0f) *alpha = 1.0f; - //selector.x = bounds.x + (int)(((alpha - 0)/(100 - 0))*(bounds.width - 2*GuiGetStyle(SLIDER, BORDER_WIDTH))) - selector.width/2; - } - else state = STATE_FOCUSED; - } - } - //-------------------------------------------------------------------- - - // Draw control - //-------------------------------------------------------------------- - - // Draw alpha bar: checked background - if (state != STATE_DISABLED) - { - int checksX = (int)bounds.width/RAYGUI_COLORBARALPHA_CHECKED_SIZE; - int checksY = (int)bounds.height/RAYGUI_COLORBARALPHA_CHECKED_SIZE; - - for (int x = 0; x < checksX; x++) - { - for (int y = 0; y < checksY; y++) - { - Rectangle check = { bounds.x + x*RAYGUI_COLORBARALPHA_CHECKED_SIZE, bounds.y + y*RAYGUI_COLORBARALPHA_CHECKED_SIZE, RAYGUI_COLORBARALPHA_CHECKED_SIZE, RAYGUI_COLORBARALPHA_CHECKED_SIZE }; - GuiDrawRectangle(check, 0, BLANK, ((x + y)%2)? Fade(GetColor(GuiGetStyle(COLORPICKER, BORDER_COLOR_DISABLED)), 0.4f) : Fade(GetColor(GuiGetStyle(COLORPICKER, BASE_COLOR_DISABLED)), 0.4f)); - } - } - - DrawRectangleGradientEx(bounds, RAYGUI_CLITERAL(Color){ 255, 255, 255, 0 }, RAYGUI_CLITERAL(Color){ 255, 255, 255, 0 }, Fade(RAYGUI_CLITERAL(Color){ 0, 0, 0, 255 }, guiAlpha), Fade(RAYGUI_CLITERAL(Color){ 0, 0, 0, 255 }, guiAlpha)); - } - else DrawRectangleGradientEx(bounds, Fade(GetColor(GuiGetStyle(COLORPICKER, BASE_COLOR_DISABLED)), 0.1f), Fade(GetColor(GuiGetStyle(COLORPICKER, BASE_COLOR_DISABLED)), 0.1f), Fade(GetColor(GuiGetStyle(COLORPICKER, BORDER_COLOR_DISABLED)), guiAlpha), Fade(GetColor(GuiGetStyle(COLORPICKER, BORDER_COLOR_DISABLED)), guiAlpha)); - - GuiDrawRectangle(bounds, GuiGetStyle(COLORPICKER, BORDER_WIDTH), GetColor(GuiGetStyle(COLORPICKER, BORDER + state*3)), BLANK); - - // Draw alpha bar: selector - GuiDrawRectangle(selector, 0, BLANK, GetColor(GuiGetStyle(COLORPICKER, BORDER + state*3))); - //-------------------------------------------------------------------- - - return result; -} - -// Color Bar Hue control -// Returns hue value normalized [0..1] -// NOTE: Other similar bars (for reference): -// Color GuiColorBarSat() [WHITE->color] -// Color GuiColorBarValue() [BLACK->color], HSV/HSL -// float GuiColorBarLuminance() [BLACK->WHITE] -int GuiColorBarHue(Rectangle bounds, const char *text, float *hue) -{ - int result = 0; - GuiState state = guiState; - Rectangle selector = { (float)bounds.x - GuiGetStyle(COLORPICKER, HUEBAR_SELECTOR_OVERFLOW), (float)bounds.y + (*hue)/360.0f*bounds.height - GuiGetStyle(COLORPICKER, HUEBAR_SELECTOR_HEIGHT)/2, (float)bounds.width + GuiGetStyle(COLORPICKER, HUEBAR_SELECTOR_OVERFLOW)*2, (float)GuiGetStyle(COLORPICKER, HUEBAR_SELECTOR_HEIGHT) }; - - // Update control - //-------------------------------------------------------------------- - if ((state != STATE_DISABLED) && !guiLocked) - { - Vector2 mousePoint = GetMousePosition(); - - if (guiControlExclusiveMode) // Allows to keep dragging outside of bounds - { - if (IsMouseButtonDown(MOUSE_LEFT_BUTTON)) - { - if (CHECK_BOUNDS_ID(bounds, guiControlExclusiveRec)) - { - state = STATE_PRESSED; - - *hue = (mousePoint.y - bounds.y)*360/bounds.height; - if (*hue <= 0.0f) *hue = 0.0f; - if (*hue >= 359.0f) *hue = 359.0f; - } - } - else - { - guiControlExclusiveMode = false; - guiControlExclusiveRec = RAYGUI_CLITERAL(Rectangle){ 0, 0, 0, 0 }; - } - } - else if (CheckCollisionPointRec(mousePoint, bounds) || CheckCollisionPointRec(mousePoint, selector)) - { - if (IsMouseButtonDown(MOUSE_LEFT_BUTTON)) - { - state = STATE_PRESSED; - guiControlExclusiveMode = true; - guiControlExclusiveRec = bounds; // Store bounds as an identifier when dragging starts - - *hue = (mousePoint.y - bounds.y)*360/bounds.height; - if (*hue <= 0.0f) *hue = 0.0f; - if (*hue >= 359.0f) *hue = 359.0f; - - } - else state = STATE_FOCUSED; - - /*if (IsKeyDown(KEY_UP)) - { - hue -= 2.0f; - if (hue <= 0.0f) hue = 0.0f; - } - else if (IsKeyDown(KEY_DOWN)) - { - hue += 2.0f; - if (hue >= 360.0f) hue = 360.0f; - }*/ - } - } - //-------------------------------------------------------------------- - - // Draw control - //-------------------------------------------------------------------- - if (state != STATE_DISABLED) - { - // Draw hue bar:color bars - // TODO: Use directly DrawRectangleGradientEx(bounds, color1, color2, color2, color1); - DrawRectangleGradientV((int)bounds.x, (int)(bounds.y), (int)bounds.width, (int)ceilf(bounds.height/6), Fade(RAYGUI_CLITERAL(Color){ 255, 0, 0, 255 }, guiAlpha), Fade(RAYGUI_CLITERAL(Color){ 255, 255, 0, 255 }, guiAlpha)); - DrawRectangleGradientV((int)bounds.x, (int)(bounds.y + bounds.height/6), (int)bounds.width, (int)ceilf(bounds.height/6), Fade(RAYGUI_CLITERAL(Color){ 255, 255, 0, 255 }, guiAlpha), Fade(RAYGUI_CLITERAL(Color){ 0, 255, 0, 255 }, guiAlpha)); - DrawRectangleGradientV((int)bounds.x, (int)(bounds.y + 2*(bounds.height/6)), (int)bounds.width, (int)ceilf(bounds.height/6), Fade(RAYGUI_CLITERAL(Color){ 0, 255, 0, 255 }, guiAlpha), Fade(RAYGUI_CLITERAL(Color){ 0, 255, 255, 255 }, guiAlpha)); - DrawRectangleGradientV((int)bounds.x, (int)(bounds.y + 3*(bounds.height/6)), (int)bounds.width, (int)ceilf(bounds.height/6), Fade(RAYGUI_CLITERAL(Color){ 0, 255, 255, 255 }, guiAlpha), Fade(RAYGUI_CLITERAL(Color){ 0, 0, 255, 255 }, guiAlpha)); - DrawRectangleGradientV((int)bounds.x, (int)(bounds.y + 4*(bounds.height/6)), (int)bounds.width, (int)ceilf(bounds.height/6), Fade(RAYGUI_CLITERAL(Color){ 0, 0, 255, 255 }, guiAlpha), Fade(RAYGUI_CLITERAL(Color){ 255, 0, 255, 255 }, guiAlpha)); - DrawRectangleGradientV((int)bounds.x, (int)(bounds.y + 5*(bounds.height/6)), (int)bounds.width, (int)(bounds.height/6), Fade(RAYGUI_CLITERAL(Color){ 255, 0, 255, 255 }, guiAlpha), Fade(RAYGUI_CLITERAL(Color){ 255, 0, 0, 255 }, guiAlpha)); - } - else DrawRectangleGradientV((int)bounds.x, (int)bounds.y, (int)bounds.width, (int)bounds.height, Fade(Fade(GetColor(GuiGetStyle(COLORPICKER, BASE_COLOR_DISABLED)), 0.1f), guiAlpha), Fade(GetColor(GuiGetStyle(COLORPICKER, BORDER_COLOR_DISABLED)), guiAlpha)); - - GuiDrawRectangle(bounds, GuiGetStyle(COLORPICKER, BORDER_WIDTH), GetColor(GuiGetStyle(COLORPICKER, BORDER + state*3)), BLANK); - - // Draw hue bar: selector - GuiDrawRectangle(selector, 0, BLANK, GetColor(GuiGetStyle(COLORPICKER, BORDER + state*3))); - //-------------------------------------------------------------------- - - return result; -} - -// Color Picker control -// NOTE: It's divided in multiple controls: -// Color GuiColorPanel(Rectangle bounds, Color color) -// float GuiColorBarAlpha(Rectangle bounds, float alpha) -// float GuiColorBarHue(Rectangle bounds, float value) -// NOTE: bounds define GuiColorPanel() size -// NOTE: this picker converts RGB to HSV, which can cause the Hue control to jump. If you have this problem, consider using the HSV variant instead -int GuiColorPicker(Rectangle bounds, const char *text, Color *color) -{ - int result = 0; - - Color temp = { 200, 0, 0, 255 }; - if (color == NULL) color = &temp; - - GuiColorPanel(bounds, NULL, color); - - Rectangle boundsHue = { (float)bounds.x + bounds.width + GuiGetStyle(COLORPICKER, HUEBAR_PADDING), (float)bounds.y, (float)GuiGetStyle(COLORPICKER, HUEBAR_WIDTH), (float)bounds.height }; - //Rectangle boundsAlpha = { bounds.x, bounds.y + bounds.height + GuiGetStyle(COLORPICKER, BARS_PADDING), bounds.width, GuiGetStyle(COLORPICKER, BARS_THICK) }; - - // NOTE: this conversion can cause low hue-resolution, if the r, g and b value are very similar, which causes the hue bar to shift around when only the GuiColorPanel is used. - Vector3 hsv = ConvertRGBtoHSV(RAYGUI_CLITERAL(Vector3){ (*color).r/255.0f, (*color).g/255.0f, (*color).b/255.0f }); - - GuiColorBarHue(boundsHue, NULL, &hsv.x); - - //color.a = (unsigned char)(GuiColorBarAlpha(boundsAlpha, (float)color.a/255.0f)*255.0f); - Vector3 rgb = ConvertHSVtoRGB(hsv); - - *color = RAYGUI_CLITERAL(Color){ (unsigned char)roundf(rgb.x*255.0f), (unsigned char)roundf(rgb.y*255.0f), (unsigned char)roundf(rgb.z*255.0f), (*color).a }; - - return result; -} - -// Color Picker control that avoids conversion to RGB and back to HSV on each call, thus avoiding jittering. -// The user can call ConvertHSVtoRGB() to convert *colorHsv value to RGB. -// NOTE: It's divided in multiple controls: -// int GuiColorPanelHSV(Rectangle bounds, const char *text, Vector3 *colorHsv) -// int GuiColorBarAlpha(Rectangle bounds, const char *text, float *alpha) -// float GuiColorBarHue(Rectangle bounds, float value) -// NOTE: bounds define GuiColorPanelHSV() size -int GuiColorPickerHSV(Rectangle bounds, const char *text, Vector3 *colorHsv) -{ - int result = 0; - - Vector3 tempHsv = { 0 }; - - if (colorHsv == NULL) - { - const Vector3 tempColor = { 200.0f/255.0f, 0.0f, 0.0f }; - tempHsv = ConvertRGBtoHSV(tempColor); - colorHsv = &tempHsv; - } - - GuiColorPanelHSV(bounds, NULL, colorHsv); - - const Rectangle boundsHue = { (float)bounds.x + bounds.width + GuiGetStyle(COLORPICKER, HUEBAR_PADDING), (float)bounds.y, (float)GuiGetStyle(COLORPICKER, HUEBAR_WIDTH), (float)bounds.height }; - - GuiColorBarHue(boundsHue, NULL, &colorHsv->x); - - return result; -} - -// Color Panel control - HSV variant -int GuiColorPanelHSV(Rectangle bounds, const char *text, Vector3 *colorHsv) -{ - int result = 0; - GuiState state = guiState; - Vector2 pickerSelector = { 0 }; - - const Color colWhite = { 255, 255, 255, 255 }; - const Color colBlack = { 0, 0, 0, 255 }; - - pickerSelector.x = bounds.x + (float)colorHsv->y*bounds.width; // HSV: Saturation - pickerSelector.y = bounds.y + (1.0f - (float)colorHsv->z)*bounds.height; // HSV: Value - - Vector3 maxHue = { colorHsv->x, 1.0f, 1.0f }; - Vector3 rgbHue = ConvertHSVtoRGB(maxHue); - Color maxHueCol = { (unsigned char)(255.0f*rgbHue.x), - (unsigned char)(255.0f*rgbHue.y), - (unsigned char)(255.0f*rgbHue.z), 255 }; - - // Update control - //-------------------------------------------------------------------- - if ((state != STATE_DISABLED) && !guiLocked) - { - Vector2 mousePoint = GetMousePosition(); - - if (guiControlExclusiveMode) // Allows to keep dragging outside of bounds - { - if (IsMouseButtonDown(MOUSE_LEFT_BUTTON)) - { - if (CHECK_BOUNDS_ID(bounds, guiControlExclusiveRec)) - { - pickerSelector = mousePoint; - - if (pickerSelector.x < bounds.x) pickerSelector.x = bounds.x; - if (pickerSelector.x > bounds.x + bounds.width) pickerSelector.x = bounds.x + bounds.width; - if (pickerSelector.y < bounds.y) pickerSelector.y = bounds.y; - if (pickerSelector.y > bounds.y + bounds.height) pickerSelector.y = bounds.y + bounds.height; - - // Calculate color from picker - Vector2 colorPick = { pickerSelector.x - bounds.x, pickerSelector.y - bounds.y }; - - colorPick.x /= (float)bounds.width; // Get normalized value on x - colorPick.y /= (float)bounds.height; // Get normalized value on y - - colorHsv->y = colorPick.x; - colorHsv->z = 1.0f - colorPick.y; - - } - } - else - { - guiControlExclusiveMode = false; - guiControlExclusiveRec = RAYGUI_CLITERAL(Rectangle){ 0, 0, 0, 0 }; - } - } - else if (CheckCollisionPointRec(mousePoint, bounds)) - { - if (IsMouseButtonDown(MOUSE_LEFT_BUTTON)) - { - state = STATE_PRESSED; - guiControlExclusiveMode = true; - guiControlExclusiveRec = bounds; - pickerSelector = mousePoint; - - // Calculate color from picker - Vector2 colorPick = { pickerSelector.x - bounds.x, pickerSelector.y - bounds.y }; - - colorPick.x /= (float)bounds.width; // Get normalized value on x - colorPick.y /= (float)bounds.height; // Get normalized value on y - - colorHsv->y = colorPick.x; - colorHsv->z = 1.0f - colorPick.y; - } - else state = STATE_FOCUSED; - } - } - //-------------------------------------------------------------------- - - // Draw control - //-------------------------------------------------------------------- - if (state != STATE_DISABLED) - { - DrawRectangleGradientEx(bounds, Fade(colWhite, guiAlpha), Fade(colWhite, guiAlpha), Fade(maxHueCol, guiAlpha), Fade(maxHueCol, guiAlpha)); - DrawRectangleGradientEx(bounds, Fade(colBlack, 0), Fade(colBlack, guiAlpha), Fade(colBlack, guiAlpha), Fade(colBlack, 0)); - - // Draw color picker: selector - Rectangle selector = { pickerSelector.x - GuiGetStyle(COLORPICKER, COLOR_SELECTOR_SIZE)/2, pickerSelector.y - GuiGetStyle(COLORPICKER, COLOR_SELECTOR_SIZE)/2, (float)GuiGetStyle(COLORPICKER, COLOR_SELECTOR_SIZE), (float)GuiGetStyle(COLORPICKER, COLOR_SELECTOR_SIZE) }; - GuiDrawRectangle(selector, 0, BLANK, colWhite); - } - else - { - DrawRectangleGradientEx(bounds, Fade(Fade(GetColor(GuiGetStyle(COLORPICKER, BASE_COLOR_DISABLED)), 0.1f), guiAlpha), Fade(Fade(colBlack, 0.6f), guiAlpha), Fade(Fade(colBlack, 0.6f), guiAlpha), Fade(Fade(GetColor(GuiGetStyle(COLORPICKER, BORDER_COLOR_DISABLED)), 0.6f), guiAlpha)); - } - - GuiDrawRectangle(bounds, GuiGetStyle(COLORPICKER, BORDER_WIDTH), GetColor(GuiGetStyle(COLORPICKER, BORDER + state*3)), BLANK); - //-------------------------------------------------------------------- - - return result; -} - -// Message Box control -int GuiMessageBox(Rectangle bounds, const char *title, const char *message, const char *buttons) -{ - #if !defined(RAYGUI_MESSAGEBOX_BUTTON_HEIGHT) - #define RAYGUI_MESSAGEBOX_BUTTON_HEIGHT 24 - #endif - #if !defined(RAYGUI_MESSAGEBOX_BUTTON_PADDING) - #define RAYGUI_MESSAGEBOX_BUTTON_PADDING 12 - #endif - - int result = -1; // Returns clicked button from buttons list, 0 refers to closed window button - - int buttonCount = 0; - const char **buttonsText = GuiTextSplit(buttons, ';', &buttonCount, NULL); - Rectangle buttonBounds = { 0 }; - buttonBounds.x = bounds.x + RAYGUI_MESSAGEBOX_BUTTON_PADDING; - buttonBounds.y = bounds.y + bounds.height - RAYGUI_MESSAGEBOX_BUTTON_HEIGHT - RAYGUI_MESSAGEBOX_BUTTON_PADDING; - buttonBounds.width = (bounds.width - RAYGUI_MESSAGEBOX_BUTTON_PADDING*(buttonCount + 1))/buttonCount; - buttonBounds.height = RAYGUI_MESSAGEBOX_BUTTON_HEIGHT; - - //int textWidth = GetTextWidth(message) + 2; - - Rectangle textBounds = { 0 }; - textBounds.x = bounds.x + RAYGUI_MESSAGEBOX_BUTTON_PADDING; - textBounds.y = bounds.y + RAYGUI_WINDOWBOX_STATUSBAR_HEIGHT + RAYGUI_MESSAGEBOX_BUTTON_PADDING; - textBounds.width = bounds.width - RAYGUI_MESSAGEBOX_BUTTON_PADDING*2; - textBounds.height = bounds.height - RAYGUI_WINDOWBOX_STATUSBAR_HEIGHT - 3*RAYGUI_MESSAGEBOX_BUTTON_PADDING - RAYGUI_MESSAGEBOX_BUTTON_HEIGHT; - - // Draw control - //-------------------------------------------------------------------- - if (GuiWindowBox(bounds, title)) result = 0; - - int prevTextAlignment = GuiGetStyle(LABEL, TEXT_ALIGNMENT); - GuiSetStyle(LABEL, TEXT_ALIGNMENT, TEXT_ALIGN_CENTER); - GuiLabel(textBounds, message); - GuiSetStyle(LABEL, TEXT_ALIGNMENT, prevTextAlignment); - - prevTextAlignment = GuiGetStyle(BUTTON, TEXT_ALIGNMENT); - GuiSetStyle(BUTTON, TEXT_ALIGNMENT, TEXT_ALIGN_CENTER); - - for (int i = 0; i < buttonCount; i++) - { - if (GuiButton(buttonBounds, buttonsText[i])) result = i + 1; - buttonBounds.x += (buttonBounds.width + RAYGUI_MESSAGEBOX_BUTTON_PADDING); - } - - GuiSetStyle(BUTTON, TEXT_ALIGNMENT, prevTextAlignment); - //-------------------------------------------------------------------- - - return result; -} - -// Text Input Box control, ask for text -int GuiTextInputBox(Rectangle bounds, const char *title, const char *message, const char *buttons, char *text, int textMaxSize, bool *secretViewActive) -{ - #if !defined(RAYGUI_TEXTINPUTBOX_BUTTON_HEIGHT) - #define RAYGUI_TEXTINPUTBOX_BUTTON_HEIGHT 24 - #endif - #if !defined(RAYGUI_TEXTINPUTBOX_BUTTON_PADDING) - #define RAYGUI_TEXTINPUTBOX_BUTTON_PADDING 12 - #endif - #if !defined(RAYGUI_TEXTINPUTBOX_HEIGHT) - #define RAYGUI_TEXTINPUTBOX_HEIGHT 26 - #endif - - // Used to enable text edit mode - // WARNING: No more than one GuiTextInputBox() should be open at the same time - static bool textEditMode = false; - - int result = -1; - - int buttonCount = 0; - const char **buttonsText = GuiTextSplit(buttons, ';', &buttonCount, NULL); - Rectangle buttonBounds = { 0 }; - buttonBounds.x = bounds.x + RAYGUI_TEXTINPUTBOX_BUTTON_PADDING; - buttonBounds.y = bounds.y + bounds.height - RAYGUI_TEXTINPUTBOX_BUTTON_HEIGHT - RAYGUI_TEXTINPUTBOX_BUTTON_PADDING; - buttonBounds.width = (bounds.width - RAYGUI_TEXTINPUTBOX_BUTTON_PADDING*(buttonCount + 1))/buttonCount; - buttonBounds.height = RAYGUI_TEXTINPUTBOX_BUTTON_HEIGHT; - - int messageInputHeight = (int)bounds.height - RAYGUI_WINDOWBOX_STATUSBAR_HEIGHT - GuiGetStyle(STATUSBAR, BORDER_WIDTH) - RAYGUI_TEXTINPUTBOX_BUTTON_HEIGHT - 2*RAYGUI_TEXTINPUTBOX_BUTTON_PADDING; - - Rectangle textBounds = { 0 }; - if (message != NULL) - { - int textSize = GetTextWidth(message) + 2; - - textBounds.x = bounds.x + bounds.width/2 - textSize/2; - textBounds.y = bounds.y + RAYGUI_WINDOWBOX_STATUSBAR_HEIGHT + messageInputHeight/4 - (float)GuiGetStyle(DEFAULT, TEXT_SIZE)/2; - textBounds.width = (float)textSize; - textBounds.height = (float)GuiGetStyle(DEFAULT, TEXT_SIZE); - } - - Rectangle textBoxBounds = { 0 }; - textBoxBounds.x = bounds.x + RAYGUI_TEXTINPUTBOX_BUTTON_PADDING; - textBoxBounds.y = bounds.y + RAYGUI_WINDOWBOX_STATUSBAR_HEIGHT - RAYGUI_TEXTINPUTBOX_HEIGHT/2; - if (message == NULL) textBoxBounds.y = bounds.y + 24 + RAYGUI_TEXTINPUTBOX_BUTTON_PADDING; - else textBoxBounds.y += (messageInputHeight/2 + messageInputHeight/4); - textBoxBounds.width = bounds.width - RAYGUI_TEXTINPUTBOX_BUTTON_PADDING*2; - textBoxBounds.height = RAYGUI_TEXTINPUTBOX_HEIGHT; - - // Draw control - //-------------------------------------------------------------------- - if (GuiWindowBox(bounds, title)) result = 0; - - // Draw message if available - if (message != NULL) - { - int prevTextAlignment = GuiGetStyle(LABEL, TEXT_ALIGNMENT); - GuiSetStyle(LABEL, TEXT_ALIGNMENT, TEXT_ALIGN_CENTER); - GuiLabel(textBounds, message); - GuiSetStyle(LABEL, TEXT_ALIGNMENT, prevTextAlignment); - } - - if (secretViewActive != NULL) - { - static char stars[] = "****************"; - if (GuiTextBox(RAYGUI_CLITERAL(Rectangle){ textBoxBounds.x, textBoxBounds.y, textBoxBounds.width - 4 - RAYGUI_TEXTINPUTBOX_HEIGHT, textBoxBounds.height }, - ((*secretViewActive == 1) || textEditMode)? text : stars, textMaxSize, textEditMode)) textEditMode = !textEditMode; - - GuiToggle(RAYGUI_CLITERAL(Rectangle){ textBoxBounds.x + textBoxBounds.width - RAYGUI_TEXTINPUTBOX_HEIGHT, textBoxBounds.y, RAYGUI_TEXTINPUTBOX_HEIGHT, RAYGUI_TEXTINPUTBOX_HEIGHT }, (*secretViewActive == 1)? "#44#" : "#45#", secretViewActive); - } - else - { - if (GuiTextBox(textBoxBounds, text, textMaxSize, textEditMode)) textEditMode = !textEditMode; - } - - int prevBtnTextAlignment = GuiGetStyle(BUTTON, TEXT_ALIGNMENT); - GuiSetStyle(BUTTON, TEXT_ALIGNMENT, TEXT_ALIGN_CENTER); - - for (int i = 0; i < buttonCount; i++) - { - if (GuiButton(buttonBounds, buttonsText[i])) result = i + 1; - buttonBounds.x += (buttonBounds.width + RAYGUI_MESSAGEBOX_BUTTON_PADDING); - } - - if (result >= 0) textEditMode = false; - - GuiSetStyle(BUTTON, TEXT_ALIGNMENT, prevBtnTextAlignment); - //-------------------------------------------------------------------- - - return result; // Result is the pressed button index -} - -// Grid control -// NOTE: Returns grid mouse-hover selected cell -// About drawing lines at subpixel spacing, simple put, not easy solution: -// https://stackoverflow.com/questions/4435450/2d-opengl-drawing-lines-that-dont-exactly-fit-pixel-raster -int GuiGrid(Rectangle bounds, const char *text, float spacing, int subdivs, Vector2 *mouseCell) -{ - // Grid lines alpha amount - #if !defined(RAYGUI_GRID_ALPHA) - #define RAYGUI_GRID_ALPHA 0.15f - #endif - - int result = 0; - GuiState state = guiState; - - Vector2 mousePoint = GetMousePosition(); - Vector2 currentMouseCell = { -1, -1 }; - - float spaceWidth = spacing/(float)subdivs; - int linesV = (int)(bounds.width/spaceWidth) + 1; - int linesH = (int)(bounds.height/spaceWidth) + 1; - - int color = GuiGetStyle(DEFAULT, LINE_COLOR); - - // Update control - //-------------------------------------------------------------------- - if ((state != STATE_DISABLED) && !guiLocked && !guiControlExclusiveMode) - { - if (CheckCollisionPointRec(mousePoint, bounds)) - { - // NOTE: Cell values must be the upper left of the cell the mouse is in - currentMouseCell.x = floorf((mousePoint.x - bounds.x)/spacing); - currentMouseCell.y = floorf((mousePoint.y - bounds.y)/spacing); - } - } - //-------------------------------------------------------------------- - - // Draw control - //-------------------------------------------------------------------- - if (state == STATE_DISABLED) color = GuiGetStyle(DEFAULT, BORDER_COLOR_DISABLED); - - if (subdivs > 0) - { - // Draw vertical grid lines - for (int i = 0; i < linesV; i++) - { - Rectangle lineV = { bounds.x + spacing*i/subdivs, bounds.y, 1, bounds.height + 1 }; - GuiDrawRectangle(lineV, 0, BLANK, ((i%subdivs) == 0)? GuiFade(GetColor(color), RAYGUI_GRID_ALPHA*4) : GuiFade(GetColor(color), RAYGUI_GRID_ALPHA)); - } - - // Draw horizontal grid lines - for (int i = 0; i < linesH; i++) - { - Rectangle lineH = { bounds.x, bounds.y + spacing*i/subdivs, bounds.width + 1, 1 }; - GuiDrawRectangle(lineH, 0, BLANK, ((i%subdivs) == 0)? GuiFade(GetColor(color), RAYGUI_GRID_ALPHA*4) : GuiFade(GetColor(color), RAYGUI_GRID_ALPHA)); - } - } - - if (mouseCell != NULL) *mouseCell = currentMouseCell; - return result; -} - -//---------------------------------------------------------------------------------- -// Tooltip management functions -// NOTE: Tooltips requires some global variables: tooltipPtr -//---------------------------------------------------------------------------------- -// Enable gui tooltips (global state) -void GuiEnableTooltip(void) { guiTooltip = true; } - -// Disable gui tooltips (global state) -void GuiDisableTooltip(void) { guiTooltip = false; } - -// Set tooltip string -void GuiSetTooltip(const char *tooltip) { guiTooltipPtr = tooltip; } - -//---------------------------------------------------------------------------------- -// Styles loading functions -//---------------------------------------------------------------------------------- - -// Load raygui style file (.rgs) -// NOTE: By default a binary file is expected, that file could contain a custom font, -// in that case, custom font image atlas is GRAY+ALPHA and pixel data can be compressed (DEFLATE) -void GuiLoadStyle(const char *fileName) -{ - #define MAX_LINE_BUFFER_SIZE 256 - - bool tryBinary = false; - if (!guiStyleLoaded) GuiLoadStyleDefault(); - - // Try reading the files as text file first - FILE *rgsFile = fopen(fileName, "rt"); - - if (rgsFile != NULL) - { - char buffer[MAX_LINE_BUFFER_SIZE] = { 0 }; - fgets(buffer, MAX_LINE_BUFFER_SIZE, rgsFile); - - if (buffer[0] == '#') - { - int controlId = 0; - int propertyId = 0; - unsigned int propertyValue = 0; - - while (!feof(rgsFile)) - { - switch (buffer[0]) - { - case 'p': - { - // Style property: p - - sscanf(buffer, "p %d %d 0x%x", &controlId, &propertyId, &propertyValue); - GuiSetStyle(controlId, propertyId, (int)propertyValue); - - } break; - case 'f': - { - // Style font: f - - int fontSize = 0; - char charmapFileName[256] = { 0 }; - char fontFileName[256] = { 0 }; - sscanf(buffer, "f %d %s %[^\r\n]s", &fontSize, charmapFileName, fontFileName); - - Font font = { 0 }; - int *codepoints = NULL; - int codepointCount = 0; - - if (charmapFileName[0] != '0') - { - // Load text data from file - // NOTE: Expected an UTF-8 array of codepoints, no separation - char *textData = LoadFileText(TextFormat("%s/%s", GetDirectoryPath(fileName), charmapFileName)); - codepoints = LoadCodepoints(textData, &codepointCount); - UnloadFileText(textData); - } - - if (fontFileName[0] != '\0') - { - // In case a font is already loaded and it is not default internal font, unload it - if (font.texture.id != GetFontDefault().texture.id) UnloadTexture(font.texture); - - if (codepointCount > 0) font = LoadFontEx(TextFormat("%s/%s", GetDirectoryPath(fileName), fontFileName), fontSize, codepoints, codepointCount); - else font = LoadFontEx(TextFormat("%s/%s", GetDirectoryPath(fileName), fontFileName), fontSize, NULL, 0); // Default to 95 standard codepoints - } - - // If font texture not properly loaded, revert to default font and size/spacing - if (font.texture.id == 0) - { - font = GetFontDefault(); - GuiSetStyle(DEFAULT, TEXT_SIZE, 10); - GuiSetStyle(DEFAULT, TEXT_SPACING, 1); - } - - UnloadCodepoints(codepoints); - - if ((font.texture.id > 0) && (font.glyphCount > 0)) GuiSetFont(font); - - } break; - default: break; - } - - fgets(buffer, MAX_LINE_BUFFER_SIZE, rgsFile); - } - } - else tryBinary = true; - - fclose(rgsFile); - } - - if (tryBinary) - { - rgsFile = fopen(fileName, "rb"); - - if (rgsFile != NULL) - { - fseek(rgsFile, 0, SEEK_END); - int fileDataSize = ftell(rgsFile); - fseek(rgsFile, 0, SEEK_SET); - - if (fileDataSize > 0) - { - unsigned char *fileData = (unsigned char *)RAYGUI_MALLOC(fileDataSize*sizeof(unsigned char)); - fread(fileData, sizeof(unsigned char), fileDataSize, rgsFile); - - GuiLoadStyleFromMemory(fileData, fileDataSize); - - RAYGUI_FREE(fileData); - } - - fclose(rgsFile); - } - } -} - -// Load style default over global style -void GuiLoadStyleDefault(void) -{ - // We set this variable first to avoid cyclic function calls - // when calling GuiSetStyle() and GuiGetStyle() - guiStyleLoaded = true; - - // Initialize default LIGHT style property values - // WARNING: Default value are applied to all controls on set but - // they can be overwritten later on for every custom control - GuiSetStyle(DEFAULT, BORDER_COLOR_NORMAL, 0x838383ff); - GuiSetStyle(DEFAULT, BASE_COLOR_NORMAL, 0xc9c9c9ff); - GuiSetStyle(DEFAULT, TEXT_COLOR_NORMAL, 0x686868ff); - GuiSetStyle(DEFAULT, BORDER_COLOR_FOCUSED, 0x5bb2d9ff); - GuiSetStyle(DEFAULT, BASE_COLOR_FOCUSED, 0xc9effeff); - GuiSetStyle(DEFAULT, TEXT_COLOR_FOCUSED, 0x6c9bbcff); - GuiSetStyle(DEFAULT, BORDER_COLOR_PRESSED, 0x0492c7ff); - GuiSetStyle(DEFAULT, BASE_COLOR_PRESSED, 0x97e8ffff); - GuiSetStyle(DEFAULT, TEXT_COLOR_PRESSED, 0x368bafff); - GuiSetStyle(DEFAULT, BORDER_COLOR_DISABLED, 0xb5c1c2ff); - GuiSetStyle(DEFAULT, BASE_COLOR_DISABLED, 0xe6e9e9ff); - GuiSetStyle(DEFAULT, TEXT_COLOR_DISABLED, 0xaeb7b8ff); - GuiSetStyle(DEFAULT, BORDER_WIDTH, 1); - GuiSetStyle(DEFAULT, TEXT_PADDING, 0); - GuiSetStyle(DEFAULT, TEXT_ALIGNMENT, TEXT_ALIGN_CENTER); - - // Initialize default extended property values - // NOTE: By default, extended property values are initialized to 0 - GuiSetStyle(DEFAULT, TEXT_SIZE, 10); // DEFAULT, shared by all controls - GuiSetStyle(DEFAULT, TEXT_SPACING, 1); // DEFAULT, shared by all controls - GuiSetStyle(DEFAULT, LINE_COLOR, 0x90abb5ff); // DEFAULT specific property - GuiSetStyle(DEFAULT, BACKGROUND_COLOR, 0xf5f5f5ff); // DEFAULT specific property - GuiSetStyle(DEFAULT, TEXT_LINE_SPACING, 15); // DEFAULT, 15 pixels between lines - GuiSetStyle(DEFAULT, TEXT_ALIGNMENT_VERTICAL, TEXT_ALIGN_MIDDLE); // DEFAULT, text aligned vertically to middle of text-bounds - - // Initialize control-specific property values - // NOTE: Those properties are in default list but require specific values by control type - GuiSetStyle(LABEL, TEXT_ALIGNMENT, TEXT_ALIGN_LEFT); - GuiSetStyle(BUTTON, BORDER_WIDTH, 2); - GuiSetStyle(SLIDER, TEXT_PADDING, 4); - GuiSetStyle(PROGRESSBAR, TEXT_PADDING, 4); - GuiSetStyle(CHECKBOX, TEXT_PADDING, 4); - GuiSetStyle(CHECKBOX, TEXT_ALIGNMENT, TEXT_ALIGN_RIGHT); - GuiSetStyle(DROPDOWNBOX, TEXT_PADDING, 0); - GuiSetStyle(DROPDOWNBOX, TEXT_ALIGNMENT, TEXT_ALIGN_CENTER); - GuiSetStyle(TEXTBOX, TEXT_PADDING, 4); - GuiSetStyle(TEXTBOX, TEXT_ALIGNMENT, TEXT_ALIGN_LEFT); - GuiSetStyle(VALUEBOX, TEXT_PADDING, 0); - GuiSetStyle(VALUEBOX, TEXT_ALIGNMENT, TEXT_ALIGN_LEFT); - GuiSetStyle(SPINNER, TEXT_PADDING, 0); - GuiSetStyle(SPINNER, TEXT_ALIGNMENT, TEXT_ALIGN_LEFT); - GuiSetStyle(STATUSBAR, TEXT_PADDING, 8); - GuiSetStyle(STATUSBAR, TEXT_ALIGNMENT, TEXT_ALIGN_LEFT); - - // Initialize extended property values - // NOTE: By default, extended property values are initialized to 0 - GuiSetStyle(TOGGLE, GROUP_PADDING, 2); - GuiSetStyle(SLIDER, SLIDER_WIDTH, 16); - GuiSetStyle(SLIDER, SLIDER_PADDING, 1); - GuiSetStyle(PROGRESSBAR, PROGRESS_PADDING, 1); - GuiSetStyle(CHECKBOX, CHECK_PADDING, 1); - GuiSetStyle(COMBOBOX, COMBO_BUTTON_WIDTH, 32); - GuiSetStyle(COMBOBOX, COMBO_BUTTON_SPACING, 2); - GuiSetStyle(DROPDOWNBOX, ARROW_PADDING, 16); - GuiSetStyle(DROPDOWNBOX, DROPDOWN_ITEMS_SPACING, 2); - GuiSetStyle(SPINNER, SPIN_BUTTON_WIDTH, 24); - GuiSetStyle(SPINNER, SPIN_BUTTON_SPACING, 2); - GuiSetStyle(SCROLLBAR, BORDER_WIDTH, 0); - GuiSetStyle(SCROLLBAR, ARROWS_VISIBLE, 0); - GuiSetStyle(SCROLLBAR, ARROWS_SIZE, 6); - GuiSetStyle(SCROLLBAR, SCROLL_SLIDER_PADDING, 0); - GuiSetStyle(SCROLLBAR, SCROLL_SLIDER_SIZE, 16); - GuiSetStyle(SCROLLBAR, SCROLL_PADDING, 0); - GuiSetStyle(SCROLLBAR, SCROLL_SPEED, 12); - GuiSetStyle(LISTVIEW, LIST_ITEMS_HEIGHT, 28); - GuiSetStyle(LISTVIEW, LIST_ITEMS_SPACING, 2); - GuiSetStyle(LISTVIEW, SCROLLBAR_WIDTH, 12); - GuiSetStyle(LISTVIEW, SCROLLBAR_SIDE, SCROLLBAR_RIGHT_SIDE); - GuiSetStyle(COLORPICKER, COLOR_SELECTOR_SIZE, 8); - GuiSetStyle(COLORPICKER, HUEBAR_WIDTH, 16); - GuiSetStyle(COLORPICKER, HUEBAR_PADDING, 8); - GuiSetStyle(COLORPICKER, HUEBAR_SELECTOR_HEIGHT, 8); - GuiSetStyle(COLORPICKER, HUEBAR_SELECTOR_OVERFLOW, 2); - - if (guiFont.texture.id != GetFontDefault().texture.id) - { - // Unload previous font texture - UnloadTexture(guiFont.texture); - RL_FREE(guiFont.recs); - RL_FREE(guiFont.glyphs); - guiFont.recs = NULL; - guiFont.glyphs = NULL; - - // Setup default raylib font - guiFont = GetFontDefault(); - - // NOTE: Default raylib font character 95 is a white square - Rectangle whiteChar = guiFont.recs[95]; - - // NOTE: We set up a 1px padding on char rectangle to avoid pixel bleeding on MSAA filtering - SetShapesTexture(guiFont.texture, RAYGUI_CLITERAL(Rectangle){ whiteChar.x + 1, whiteChar.y + 1, whiteChar.width - 2, whiteChar.height - 2 }); - } -} - -// Get text with icon id prepended -// NOTE: Useful to add icons by name id (enum) instead of -// a number that can change between ricon versions -const char *GuiIconText(int iconId, const char *text) -{ -#if defined(RAYGUI_NO_ICONS) - return NULL; -#else - static char buffer[1024] = { 0 }; - static char iconBuffer[16] = { 0 }; - - if (text != NULL) - { - memset(buffer, 0, 1024); - sprintf(buffer, "#%03i#", iconId); - - for (int i = 5; i < 1024; i++) - { - buffer[i] = text[i - 5]; - if (text[i - 5] == '\0') break; - } - - return buffer; - } - else - { - sprintf(iconBuffer, "#%03i#", iconId); - - return iconBuffer; - } -#endif -} - -#if !defined(RAYGUI_NO_ICONS) -// Get full icons data pointer -unsigned int *GuiGetIcons(void) { return guiIconsPtr; } - -// Load raygui icons file (.rgi) -// NOTE: In case nameIds are required, they can be requested with loadIconsName, -// they are returned as a guiIconsName[iconCount][RAYGUI_ICON_MAX_NAME_LENGTH], -// WARNING: guiIconsName[]][] memory should be manually freed! -char **GuiLoadIcons(const char *fileName, bool loadIconsName) -{ - // Style File Structure (.rgi) - // ------------------------------------------------------ - // Offset | Size | Type | Description - // ------------------------------------------------------ - // 0 | 4 | char | Signature: "rGI " - // 4 | 2 | short | Version: 100 - // 6 | 2 | short | reserved - - // 8 | 2 | short | Num icons (N) - // 10 | 2 | short | Icons size (Options: 16, 32, 64) (S) - - // Icons name id (32 bytes per name id) - // foreach (icon) - // { - // 12+32*i | 32 | char | Icon NameId - // } - - // Icons data: One bit per pixel, stored as unsigned int array (depends on icon size) - // S*S pixels/32bit per unsigned int = K unsigned int per icon - // foreach (icon) - // { - // ... | K | unsigned int | Icon Data - // } - - FILE *rgiFile = fopen(fileName, "rb"); - - char **guiIconsName = NULL; - - if (rgiFile != NULL) - { - char signature[5] = { 0 }; - short version = 0; - short reserved = 0; - short iconCount = 0; - short iconSize = 0; - - fread(signature, 1, 4, rgiFile); - fread(&version, sizeof(short), 1, rgiFile); - fread(&reserved, sizeof(short), 1, rgiFile); - fread(&iconCount, sizeof(short), 1, rgiFile); - fread(&iconSize, sizeof(short), 1, rgiFile); - - if ((signature[0] == 'r') && - (signature[1] == 'G') && - (signature[2] == 'I') && - (signature[3] == ' ')) - { - if (loadIconsName) - { - guiIconsName = (char **)RAYGUI_MALLOC(iconCount*sizeof(char **)); - for (int i = 0; i < iconCount; i++) - { - guiIconsName[i] = (char *)RAYGUI_MALLOC(RAYGUI_ICON_MAX_NAME_LENGTH); - fread(guiIconsName[i], 1, RAYGUI_ICON_MAX_NAME_LENGTH, rgiFile); - } - } - else fseek(rgiFile, iconCount*RAYGUI_ICON_MAX_NAME_LENGTH, SEEK_CUR); - - // Read icons data directly over internal icons array - fread(guiIconsPtr, sizeof(unsigned int), iconCount*(iconSize*iconSize/32), rgiFile); - } - - fclose(rgiFile); - } - - return guiIconsName; -} - -// Draw selected icon using rectangles pixel-by-pixel -void GuiDrawIcon(int iconId, int posX, int posY, int pixelSize, Color color) -{ - #define BIT_CHECK(a,b) ((a) & (1u<<(b))) - - for (int i = 0, y = 0; i < RAYGUI_ICON_SIZE*RAYGUI_ICON_SIZE/32; i++) - { - for (int k = 0; k < 32; k++) - { - if (BIT_CHECK(guiIconsPtr[iconId*RAYGUI_ICON_DATA_ELEMENTS + i], k)) - { - #if !defined(RAYGUI_STANDALONE) - GuiDrawRectangle(RAYGUI_CLITERAL(Rectangle){ (float)posX + (k%RAYGUI_ICON_SIZE)*pixelSize, (float)posY + y*pixelSize, (float)pixelSize, (float)pixelSize }, 0, BLANK, color); - #endif - } - - if ((k == 15) || (k == 31)) y++; - } - } -} - -// Set icon drawing size -void GuiSetIconScale(int scale) -{ - if (scale >= 1) guiIconScale = scale; -} - -#endif // !RAYGUI_NO_ICONS - -//---------------------------------------------------------------------------------- -// Module specific Functions Definition -//---------------------------------------------------------------------------------- - -// Load style from memory -// WARNING: Binary files only -static void GuiLoadStyleFromMemory(const unsigned char *fileData, int dataSize) -{ - unsigned char *fileDataPtr = (unsigned char *)fileData; - - char signature[5] = { 0 }; - short version = 0; - short reserved = 0; - int propertyCount = 0; - - memcpy(signature, fileDataPtr, 4); - memcpy(&version, fileDataPtr + 4, sizeof(short)); - memcpy(&reserved, fileDataPtr + 4 + 2, sizeof(short)); - memcpy(&propertyCount, fileDataPtr + 4 + 2 + 2, sizeof(int)); - fileDataPtr += 12; - - if ((signature[0] == 'r') && - (signature[1] == 'G') && - (signature[2] == 'S') && - (signature[3] == ' ')) - { - short controlId = 0; - short propertyId = 0; - unsigned int propertyValue = 0; - - for (int i = 0; i < propertyCount; i++) - { - memcpy(&controlId, fileDataPtr, sizeof(short)); - memcpy(&propertyId, fileDataPtr + 2, sizeof(short)); - memcpy(&propertyValue, fileDataPtr + 2 + 2, sizeof(unsigned int)); - fileDataPtr += 8; - - if (controlId == 0) // DEFAULT control - { - // If a DEFAULT property is loaded, it is propagated to all controls - // NOTE: All DEFAULT properties should be defined first in the file - GuiSetStyle(0, (int)propertyId, propertyValue); - - if (propertyId < RAYGUI_MAX_PROPS_BASE) for (int j = 1; j < RAYGUI_MAX_CONTROLS; j++) GuiSetStyle(j, (int)propertyId, propertyValue); - } - else GuiSetStyle((int)controlId, (int)propertyId, propertyValue); - } - - // Font loading is highly dependant on raylib API to load font data and image - -#if !defined(RAYGUI_STANDALONE) - // Load custom font if available - int fontDataSize = 0; - memcpy(&fontDataSize, fileDataPtr, sizeof(int)); - fileDataPtr += 4; - - if (fontDataSize > 0) - { - Font font = { 0 }; - int fontType = 0; // 0-Normal, 1-SDF - - memcpy(&font.baseSize, fileDataPtr, sizeof(int)); - memcpy(&font.glyphCount, fileDataPtr + 4, sizeof(int)); - memcpy(&fontType, fileDataPtr + 4 + 4, sizeof(int)); - fileDataPtr += 12; - - // Load font white rectangle - Rectangle fontWhiteRec = { 0 }; - memcpy(&fontWhiteRec, fileDataPtr, sizeof(Rectangle)); - fileDataPtr += 16; - - // Load font image parameters - int fontImageUncompSize = 0; - int fontImageCompSize = 0; - memcpy(&fontImageUncompSize, fileDataPtr, sizeof(int)); - memcpy(&fontImageCompSize, fileDataPtr + 4, sizeof(int)); - fileDataPtr += 8; - - Image imFont = { 0 }; - imFont.mipmaps = 1; - memcpy(&imFont.width, fileDataPtr, sizeof(int)); - memcpy(&imFont.height, fileDataPtr + 4, sizeof(int)); - memcpy(&imFont.format, fileDataPtr + 4 + 4, sizeof(int)); - fileDataPtr += 12; - - if ((fontImageCompSize > 0) && (fontImageCompSize != fontImageUncompSize)) - { - // Compressed font atlas image data (DEFLATE), it requires DecompressData() - int dataUncompSize = 0; - unsigned char *compData = (unsigned char *)RAYGUI_MALLOC(fontImageCompSize); - memcpy(compData, fileDataPtr, fontImageCompSize); - fileDataPtr += fontImageCompSize; - - imFont.data = DecompressData(compData, fontImageCompSize, &dataUncompSize); - - // Security check, dataUncompSize must match the provided fontImageUncompSize - if (dataUncompSize != fontImageUncompSize) RAYGUI_LOG("WARNING: Uncompressed font atlas image data could be corrupted"); - - RAYGUI_FREE(compData); - } - else - { - // Font atlas image data is not compressed - imFont.data = (unsigned char *)RAYGUI_MALLOC(fontImageUncompSize); - memcpy(imFont.data, fileDataPtr, fontImageUncompSize); - fileDataPtr += fontImageUncompSize; - } - - if (font.texture.id != GetFontDefault().texture.id) UnloadTexture(font.texture); - font.texture = LoadTextureFromImage(imFont); - - RAYGUI_FREE(imFont.data); - - // Validate font atlas texture was loaded correctly - if (font.texture.id != 0) - { - // Load font recs data - int recsDataSize = font.glyphCount*sizeof(Rectangle); - int recsDataCompressedSize = 0; - - // WARNING: Version 400 adds the compression size parameter - if (version >= 400) - { - // RGS files version 400 support compressed recs data - memcpy(&recsDataCompressedSize, fileDataPtr, sizeof(int)); - fileDataPtr += sizeof(int); - } - - if ((recsDataCompressedSize > 0) && (recsDataCompressedSize != recsDataSize)) - { - // Recs data is compressed, uncompress it - unsigned char *recsDataCompressed = (unsigned char *)RAYGUI_MALLOC(recsDataCompressedSize); - - memcpy(recsDataCompressed, fileDataPtr, recsDataCompressedSize); - fileDataPtr += recsDataCompressedSize; - - int recsDataUncompSize = 0; - font.recs = (Rectangle *)DecompressData(recsDataCompressed, recsDataCompressedSize, &recsDataUncompSize); - - // Security check, data uncompressed size must match the expected original data size - if (recsDataUncompSize != recsDataSize) RAYGUI_LOG("WARNING: Uncompressed font recs data could be corrupted"); - - RAYGUI_FREE(recsDataCompressed); - } - else - { - // Recs data is uncompressed - font.recs = (Rectangle *)RAYGUI_CALLOC(font.glyphCount, sizeof(Rectangle)); - for (int i = 0; i < font.glyphCount; i++) - { - memcpy(&font.recs[i], fileDataPtr, sizeof(Rectangle)); - fileDataPtr += sizeof(Rectangle); - } - } - - // Load font glyphs info data - int glyphsDataSize = font.glyphCount*16; // 16 bytes data per glyph - int glyphsDataCompressedSize = 0; - - // WARNING: Version 400 adds the compression size parameter - if (version >= 400) - { - // RGS files version 400 support compressed glyphs data - memcpy(&glyphsDataCompressedSize, fileDataPtr, sizeof(int)); - fileDataPtr += sizeof(int); - } - - // Allocate required glyphs space to fill with data - font.glyphs = (GlyphInfo *)RAYGUI_CALLOC(font.glyphCount, sizeof(GlyphInfo)); - - if ((glyphsDataCompressedSize > 0) && (glyphsDataCompressedSize != glyphsDataSize)) - { - // Glyphs data is compressed, uncompress it - unsigned char *glypsDataCompressed = (unsigned char *)RAYGUI_MALLOC(glyphsDataCompressedSize); - - memcpy(glypsDataCompressed, fileDataPtr, glyphsDataCompressedSize); - fileDataPtr += glyphsDataCompressedSize; - - int glyphsDataUncompSize = 0; - unsigned char *glyphsDataUncomp = DecompressData(glypsDataCompressed, glyphsDataCompressedSize, &glyphsDataUncompSize); - - // Security check, data uncompressed size must match the expected original data size - if (glyphsDataUncompSize != glyphsDataSize) RAYGUI_LOG("WARNING: Uncompressed font glyphs data could be corrupted"); - - unsigned char *glyphsDataUncompPtr = glyphsDataUncomp; - - for (int i = 0; i < font.glyphCount; i++) - { - memcpy(&font.glyphs[i].value, glyphsDataUncompPtr, sizeof(int)); - memcpy(&font.glyphs[i].offsetX, glyphsDataUncompPtr + 4, sizeof(int)); - memcpy(&font.glyphs[i].offsetY, glyphsDataUncompPtr + 8, sizeof(int)); - memcpy(&font.glyphs[i].advanceX, glyphsDataUncompPtr + 12, sizeof(int)); - glyphsDataUncompPtr += 16; - } - - RAYGUI_FREE(glypsDataCompressed); - RAYGUI_FREE(glyphsDataUncomp); - } - else - { - // Glyphs data is uncompressed - for (int i = 0; i < font.glyphCount; i++) - { - memcpy(&font.glyphs[i].value, fileDataPtr, sizeof(int)); - memcpy(&font.glyphs[i].offsetX, fileDataPtr + 4, sizeof(int)); - memcpy(&font.glyphs[i].offsetY, fileDataPtr + 8, sizeof(int)); - memcpy(&font.glyphs[i].advanceX, fileDataPtr + 12, sizeof(int)); - fileDataPtr += 16; - } - } - } - else font = GetFontDefault(); // Fallback in case of errors loading font atlas texture - - GuiSetFont(font); - - // Set font texture source rectangle to be used as white texture to draw shapes - // NOTE: It makes possible to draw shapes and text (full UI) in a single draw call - if ((fontWhiteRec.x > 0) && - (fontWhiteRec.y > 0) && - (fontWhiteRec.width > 0) && - (fontWhiteRec.height > 0)) SetShapesTexture(font.texture, fontWhiteRec); - } -#endif - } -} - -// Gui get text width considering icon -static int GetTextWidth(const char *text) -{ - #if !defined(ICON_TEXT_PADDING) - #define ICON_TEXT_PADDING 4 - #endif - - Vector2 textSize = { 0 }; - int textIconOffset = 0; - - if ((text != NULL) && (text[0] != '\0')) - { - if (text[0] == '#') - { - for (int i = 1; (i < 5) && (text[i] != '\0'); i++) - { - if (text[i] == '#') - { - textIconOffset = i; - break; - } - } - } - - text += textIconOffset; - - // Make sure guiFont is set, GuiGetStyle() initializes it lazynessly - float fontSize = (float)GuiGetStyle(DEFAULT, TEXT_SIZE); - - // Custom MeasureText() implementation - if ((guiFont.texture.id > 0) && (text != NULL)) - { - // Get size in bytes of text, considering end of line and line break - int size = 0; - for (int i = 0; i < MAX_LINE_BUFFER_SIZE; i++) - { - if ((text[i] != '\0') && (text[i] != '\n')) size++; - else break; - } - - float scaleFactor = fontSize/(float)guiFont.baseSize; - textSize.y = (float)guiFont.baseSize*scaleFactor; - float glyphWidth = 0.0f; - - for (int i = 0, codepointSize = 0; i < size; i += codepointSize) - { - int codepoint = GetCodepointNext(&text[i], &codepointSize); - int codepointIndex = GetGlyphIndex(guiFont, codepoint); - - if (guiFont.glyphs[codepointIndex].advanceX == 0) glyphWidth = ((float)guiFont.recs[codepointIndex].width*scaleFactor); - else glyphWidth = ((float)guiFont.glyphs[codepointIndex].advanceX*scaleFactor); - - textSize.x += (glyphWidth + (float)GuiGetStyle(DEFAULT, TEXT_SPACING)); - } - } - - if (textIconOffset > 0) textSize.x += (RAYGUI_ICON_SIZE + ICON_TEXT_PADDING); - } - - return (int)textSize.x; -} - -// Get text bounds considering control bounds -static Rectangle GetTextBounds(int control, Rectangle bounds) -{ - Rectangle textBounds = bounds; - - textBounds.x = bounds.x + GuiGetStyle(control, BORDER_WIDTH); - textBounds.y = bounds.y + GuiGetStyle(control, BORDER_WIDTH) + GuiGetStyle(control, TEXT_PADDING); - textBounds.width = bounds.width - 2*GuiGetStyle(control, BORDER_WIDTH) - 2*GuiGetStyle(control, TEXT_PADDING); - textBounds.height = bounds.height - 2*GuiGetStyle(control, BORDER_WIDTH) - 2*GuiGetStyle(control, TEXT_PADDING); // NOTE: Text is processed line per line! - - // Depending on control, TEXT_PADDING and TEXT_ALIGNMENT properties could affect the text-bounds - switch (control) - { - case COMBOBOX: - case DROPDOWNBOX: - case LISTVIEW: - // TODO: Special cases (no label): COMBOBOX, DROPDOWNBOX, LISTVIEW - case SLIDER: - case CHECKBOX: - case VALUEBOX: - case SPINNER: - // TODO: More special cases (label on side): SLIDER, CHECKBOX, VALUEBOX, SPINNER - default: - { - // TODO: WARNING: TEXT_ALIGNMENT is already considered in GuiDrawText() - if (GuiGetStyle(control, TEXT_ALIGNMENT) == TEXT_ALIGN_RIGHT) textBounds.x -= GuiGetStyle(control, TEXT_PADDING); - else textBounds.x += GuiGetStyle(control, TEXT_PADDING); - } - break; - } - - return textBounds; -} - -// Get text icon if provided and move text cursor -// NOTE: We support up to 999 values for iconId -static const char *GetTextIcon(const char *text, int *iconId) -{ -#if !defined(RAYGUI_NO_ICONS) - *iconId = -1; - if (text[0] == '#') // Maybe we have an icon! - { - char iconValue[4] = { 0 }; // Maximum length for icon value: 3 digits + '\0' - - int pos = 1; - while ((pos < 4) && (text[pos] >= '0') && (text[pos] <= '9')) - { - iconValue[pos - 1] = text[pos]; - pos++; - } - - if (text[pos] == '#') - { - *iconId = TextToInteger(iconValue); - - // Move text pointer after icon - // WARNING: If only icon provided, it could point to EOL character: '\0' - if (*iconId >= 0) text += (pos + 1); - } - } -#endif - - return text; -} - -// Get text divided into lines (by line-breaks '\n') -const char **GetTextLines(const char *text, int *count) -{ - #define RAYGUI_MAX_TEXT_LINES 128 - - static const char *lines[RAYGUI_MAX_TEXT_LINES] = { 0 }; - for (int i = 0; i < RAYGUI_MAX_TEXT_LINES; i++) lines[i] = NULL; // Init NULL pointers to substrings - - int textSize = (int)strlen(text); - - lines[0] = text; - int len = 0; - *count = 1; - //int lineSize = 0; // Stores current line size, not returned - - for (int i = 0, k = 0; (i < textSize) && (*count < RAYGUI_MAX_TEXT_LINES); i++) - { - if (text[i] == '\n') - { - //lineSize = len; - k++; - lines[k] = &text[i + 1]; // WARNING: next value is valid? - len = 0; - *count += 1; - } - else len++; - } - - //lines[*count - 1].size = len; - - return lines; -} - -// Get text width to next space for provided string -static float GetNextSpaceWidth(const char *text, int *nextSpaceIndex) -{ - float width = 0; - int codepointByteCount = 0; - int codepoint = 0; - int index = 0; - float glyphWidth = 0; - float scaleFactor = (float)GuiGetStyle(DEFAULT, TEXT_SIZE)/guiFont.baseSize; - - for (int i = 0; text[i] != '\0'; i++) - { - if (text[i] != ' ') - { - codepoint = GetCodepoint(&text[i], &codepointByteCount); - index = GetGlyphIndex(guiFont, codepoint); - glyphWidth = (guiFont.glyphs[index].advanceX == 0)? guiFont.recs[index].width*scaleFactor : guiFont.glyphs[index].advanceX*scaleFactor; - width += (glyphWidth + (float)GuiGetStyle(DEFAULT, TEXT_SPACING)); - } - else - { - *nextSpaceIndex = i; - break; - } - } - - return width; -} - -// Gui draw text using default font -static void GuiDrawText(const char *text, Rectangle textBounds, int alignment, Color tint) -{ - #define TEXT_VALIGN_PIXEL_OFFSET(h) ((int)h%2) // Vertical alignment for pixel perfect - - #if !defined(ICON_TEXT_PADDING) - #define ICON_TEXT_PADDING 4 - #endif - - if ((text == NULL) || (text[0] == '\0')) return; // Security check - - // PROCEDURE: - // - Text is processed line per line - // - For every line, horizontal alignment is defined - // - For all text, vertical alignment is defined (multiline text only) - // - For every line, wordwrap mode is checked (useful for GuitextBox(), read-only) - - // Get text lines (using '\n' as delimiter) to be processed individually - // WARNING: We can't use GuiTextSplit() function because it can be already used - // before the GuiDrawText() call and its buffer is static, it would be overriden :( - int lineCount = 0; - const char **lines = GetTextLines(text, &lineCount); - - // Text style variables - //int alignment = GuiGetStyle(DEFAULT, TEXT_ALIGNMENT); - int alignmentVertical = GuiGetStyle(DEFAULT, TEXT_ALIGNMENT_VERTICAL); - int wrapMode = GuiGetStyle(DEFAULT, TEXT_WRAP_MODE); // Wrap-mode only available in read-only mode, no for text editing - - // TODO: WARNING: This totalHeight is not valid for vertical alignment in case of word-wrap - float totalHeight = (float)(lineCount*GuiGetStyle(DEFAULT, TEXT_SIZE) + (lineCount - 1)*GuiGetStyle(DEFAULT, TEXT_SIZE)/2); - float posOffsetY = 0.0f; - - for (int i = 0; i < lineCount; i++) - { - int iconId = 0; - lines[i] = GetTextIcon(lines[i], &iconId); // Check text for icon and move cursor - - // Get text position depending on alignment and iconId - //--------------------------------------------------------------------------------- - Vector2 textBoundsPosition = { textBounds.x, textBounds.y }; - float textBoundsWidthOffset = 0.0f; - - // NOTE: We get text size after icon has been processed - // WARNING: GetTextWidth() also processes text icon to get width! -> Really needed? - int textSizeX = GetTextWidth(lines[i]); - - // If text requires an icon, add size to measure - if (iconId >= 0) - { - textSizeX += RAYGUI_ICON_SIZE*guiIconScale; - - // WARNING: If only icon provided, text could be pointing to EOF character: '\0' -#if !defined(RAYGUI_NO_ICONS) - if ((lines[i] != NULL) && (lines[i][0] != '\0')) textSizeX += ICON_TEXT_PADDING; -#endif - } - - // Check guiTextAlign global variables - switch (alignment) - { - case TEXT_ALIGN_LEFT: textBoundsPosition.x = textBounds.x; break; - case TEXT_ALIGN_CENTER: textBoundsPosition.x = textBounds.x + textBounds.width/2 - textSizeX/2; break; - case TEXT_ALIGN_RIGHT: textBoundsPosition.x = textBounds.x + textBounds.width - textSizeX; break; - default: break; - } - - if (textSizeX > textBounds.width && (lines[i] != NULL) && (lines[i][0] != '\0')) textBoundsPosition.x = textBounds.x; - - switch (alignmentVertical) - { - // Only valid in case of wordWrap = 0; - case TEXT_ALIGN_TOP: textBoundsPosition.y = textBounds.y + posOffsetY; break; - case TEXT_ALIGN_MIDDLE: textBoundsPosition.y = textBounds.y + posOffsetY + textBounds.height/2 - totalHeight/2 + TEXT_VALIGN_PIXEL_OFFSET(textBounds.height); break; - case TEXT_ALIGN_BOTTOM: textBoundsPosition.y = textBounds.y + posOffsetY + textBounds.height - totalHeight + TEXT_VALIGN_PIXEL_OFFSET(textBounds.height); break; - default: break; - } - - // NOTE: Make sure we get pixel-perfect coordinates, - // In case of decimals we got weird text positioning - textBoundsPosition.x = (float)((int)textBoundsPosition.x); - textBoundsPosition.y = (float)((int)textBoundsPosition.y); - //--------------------------------------------------------------------------------- - - // Draw text (with icon if available) - //--------------------------------------------------------------------------------- -#if !defined(RAYGUI_NO_ICONS) - if (iconId >= 0) - { - // NOTE: We consider icon height, probably different than text size - GuiDrawIcon(iconId, (int)textBoundsPosition.x, (int)(textBounds.y + textBounds.height/2 - RAYGUI_ICON_SIZE*guiIconScale/2 + TEXT_VALIGN_PIXEL_OFFSET(textBounds.height)), guiIconScale, tint); - textBoundsPosition.x += (float)(RAYGUI_ICON_SIZE*guiIconScale + ICON_TEXT_PADDING); - textBoundsWidthOffset = (float)(RAYGUI_ICON_SIZE*guiIconScale + ICON_TEXT_PADDING); - } -#endif - // Get size in bytes of text, - // considering end of line and line break - int lineSize = 0; - for (int c = 0; (lines[i][c] != '\0') && (lines[i][c] != '\n') && (lines[i][c] != '\r'); c++, lineSize++){ } - float scaleFactor = (float)GuiGetStyle(DEFAULT, TEXT_SIZE)/guiFont.baseSize; - - int lastSpaceIndex = 0; - bool tempWrapCharMode = false; - - int textOffsetY = 0; - float textOffsetX = 0.0f; - float glyphWidth = 0; - - int ellipsisWidth = GetTextWidth("..."); - bool textOverflow = false; - for (int c = 0, codepointSize = 0; c < lineSize; c += codepointSize) - { - int codepoint = GetCodepointNext(&lines[i][c], &codepointSize); - int index = GetGlyphIndex(guiFont, codepoint); - - // NOTE: Normally we exit the decoding sequence as soon as a bad byte is found (and return 0x3f) - // but we need to draw all of the bad bytes using the '?' symbol moving one byte - if (codepoint == 0x3f) codepointSize = 1; // TODO: Review not recognized codepoints size - - // Get glyph width to check if it goes out of bounds - if (guiFont.glyphs[index].advanceX == 0) glyphWidth = ((float)guiFont.recs[index].width*scaleFactor); - else glyphWidth = (float)guiFont.glyphs[index].advanceX*scaleFactor; - - // Wrap mode text measuring, to validate if - // it can be drawn or a new line is required - if (wrapMode == TEXT_WRAP_CHAR) - { - // Jump to next line if current character reach end of the box limits - if ((textOffsetX + glyphWidth) > textBounds.width - textBoundsWidthOffset) - { - textOffsetX = 0.0f; - textOffsetY += GuiGetStyle(DEFAULT, TEXT_LINE_SPACING); - - if (tempWrapCharMode) // Wrap at char level when too long words - { - wrapMode = TEXT_WRAP_WORD; - tempWrapCharMode = false; - } - } - } - else if (wrapMode == TEXT_WRAP_WORD) - { - if (codepoint == 32) lastSpaceIndex = c; - - // Get width to next space in line - int nextSpaceIndex = 0; - float nextSpaceWidth = GetNextSpaceWidth(lines[i] + c, &nextSpaceIndex); - - int nextSpaceIndex2 = 0; - float nextWordSize = GetNextSpaceWidth(lines[i] + lastSpaceIndex + 1, &nextSpaceIndex2); - - if (nextWordSize > textBounds.width - textBoundsWidthOffset) - { - // Considering the case the next word is longer than bounds - tempWrapCharMode = true; - wrapMode = TEXT_WRAP_CHAR; - } - else if ((textOffsetX + nextSpaceWidth) > textBounds.width - textBoundsWidthOffset) - { - textOffsetX = 0.0f; - textOffsetY += GuiGetStyle(DEFAULT, TEXT_LINE_SPACING); - } - } - - if (codepoint == '\n') break; // WARNING: Lines are already processed manually, no need to keep drawing after this codepoint - else - { - // TODO: There are multiple types of spaces in Unicode, - // maybe it's a good idea to add support for more: http://jkorpela.fi/chars/spaces.html - if ((codepoint != ' ') && (codepoint != '\t')) // Do not draw codepoints with no glyph - { - if (wrapMode == TEXT_WRAP_NONE) - { - // Draw only required text glyphs fitting the textBounds.width - if (textSizeX > textBounds.width) - { - if (textOffsetX <= (textBounds.width - glyphWidth - textBoundsWidthOffset - ellipsisWidth)) - { - DrawTextCodepoint(guiFont, codepoint, RAYGUI_CLITERAL(Vector2){ textBoundsPosition.x + textOffsetX, textBoundsPosition.y + textOffsetY }, (float)GuiGetStyle(DEFAULT, TEXT_SIZE), GuiFade(tint, guiAlpha)); - } - else if (!textOverflow) - { - textOverflow = true; - - for (int j = 0; j < ellipsisWidth; j += ellipsisWidth/3) - { - DrawTextCodepoint(guiFont, '.', RAYGUI_CLITERAL(Vector2){ textBoundsPosition.x + textOffsetX + j, textBoundsPosition.y + textOffsetY }, (float)GuiGetStyle(DEFAULT, TEXT_SIZE), GuiFade(tint, guiAlpha)); - } - } - } - else - { - DrawTextCodepoint(guiFont, codepoint, RAYGUI_CLITERAL(Vector2){ textBoundsPosition.x + textOffsetX, textBoundsPosition.y + textOffsetY }, (float)GuiGetStyle(DEFAULT, TEXT_SIZE), GuiFade(tint, guiAlpha)); - } - } - else if ((wrapMode == TEXT_WRAP_CHAR) || (wrapMode == TEXT_WRAP_WORD)) - { - // Draw only glyphs inside the bounds - if ((textBoundsPosition.y + textOffsetY) <= (textBounds.y + textBounds.height - GuiGetStyle(DEFAULT, TEXT_SIZE))) - { - DrawTextCodepoint(guiFont, codepoint, RAYGUI_CLITERAL(Vector2){ textBoundsPosition.x + textOffsetX, textBoundsPosition.y + textOffsetY }, (float)GuiGetStyle(DEFAULT, TEXT_SIZE), GuiFade(tint, guiAlpha)); - } - } - } - - if (guiFont.glyphs[index].advanceX == 0) textOffsetX += ((float)guiFont.recs[index].width*scaleFactor + (float)GuiGetStyle(DEFAULT, TEXT_SPACING)); - else textOffsetX += ((float)guiFont.glyphs[index].advanceX*scaleFactor + (float)GuiGetStyle(DEFAULT, TEXT_SPACING)); - } - } - - if (wrapMode == TEXT_WRAP_NONE) posOffsetY += (float)GuiGetStyle(DEFAULT, TEXT_LINE_SPACING); - else if ((wrapMode == TEXT_WRAP_CHAR) || (wrapMode == TEXT_WRAP_WORD)) posOffsetY += (textOffsetY + (float)GuiGetStyle(DEFAULT, TEXT_LINE_SPACING)); - //--------------------------------------------------------------------------------- - } - -#if defined(RAYGUI_DEBUG_TEXT_BOUNDS) - GuiDrawRectangle(textBounds, 0, WHITE, Fade(BLUE, 0.4f)); -#endif -} - -// Gui draw rectangle using default raygui plain style with borders -static void GuiDrawRectangle(Rectangle rec, int borderWidth, Color borderColor, Color color) -{ - if (color.a > 0) - { - // Draw rectangle filled with color - DrawRectangle((int)rec.x, (int)rec.y, (int)rec.width, (int)rec.height, GuiFade(color, guiAlpha)); - } - - if (borderWidth > 0) - { - // Draw rectangle border lines with color - DrawRectangle((int)rec.x, (int)rec.y, (int)rec.width, borderWidth, GuiFade(borderColor, guiAlpha)); - DrawRectangle((int)rec.x, (int)rec.y + borderWidth, borderWidth, (int)rec.height - 2*borderWidth, GuiFade(borderColor, guiAlpha)); - DrawRectangle((int)rec.x + (int)rec.width - borderWidth, (int)rec.y + borderWidth, borderWidth, (int)rec.height - 2*borderWidth, GuiFade(borderColor, guiAlpha)); - DrawRectangle((int)rec.x, (int)rec.y + (int)rec.height - borderWidth, (int)rec.width, borderWidth, GuiFade(borderColor, guiAlpha)); - } - -#if defined(RAYGUI_DEBUG_RECS_BOUNDS) - DrawRectangle((int)rec.x, (int)rec.y, (int)rec.width, (int)rec.height, Fade(RED, 0.4f)); -#endif -} - -// Draw tooltip using control bounds -static void GuiTooltip(Rectangle controlRec) -{ - if (!guiLocked && guiTooltip && (guiTooltipPtr != NULL) && !guiControlExclusiveMode) - { - Vector2 textSize = MeasureTextEx(GuiGetFont(), guiTooltipPtr, (float)GuiGetStyle(DEFAULT, TEXT_SIZE), (float)GuiGetStyle(DEFAULT, TEXT_SPACING)); - - if ((controlRec.x + textSize.x + 16) > GetScreenWidth()) controlRec.x -= (textSize.x + 16 - controlRec.width); - - GuiPanel(RAYGUI_CLITERAL(Rectangle){ controlRec.x, controlRec.y + controlRec.height + 4, textSize.x + 16, GuiGetStyle(DEFAULT, TEXT_SIZE) + 8.f }, NULL); - - int textPadding = GuiGetStyle(LABEL, TEXT_PADDING); - int textAlignment = GuiGetStyle(LABEL, TEXT_ALIGNMENT); - GuiSetStyle(LABEL, TEXT_PADDING, 0); - GuiSetStyle(LABEL, TEXT_ALIGNMENT, TEXT_ALIGN_CENTER); - GuiLabel(RAYGUI_CLITERAL(Rectangle){ controlRec.x, controlRec.y + controlRec.height + 4, textSize.x + 16, GuiGetStyle(DEFAULT, TEXT_SIZE) + 8.f }, guiTooltipPtr); - GuiSetStyle(LABEL, TEXT_ALIGNMENT, textAlignment); - GuiSetStyle(LABEL, TEXT_PADDING, textPadding); - } -} - -// Split controls text into multiple strings -// Also check for multiple columns (required by GuiToggleGroup()) -static const char **GuiTextSplit(const char *text, char delimiter, int *count, int *textRow) -{ - // NOTE: Current implementation returns a copy of the provided string with '\0' (string end delimiter) - // inserted between strings defined by "delimiter" parameter. No memory is dynamically allocated, - // all used memory is static... it has some limitations: - // 1. Maximum number of possible split strings is set by RAYGUI_TEXTSPLIT_MAX_ITEMS - // 2. Maximum size of text to split is RAYGUI_TEXTSPLIT_MAX_TEXT_SIZE - // NOTE: Those definitions could be externally provided if required - - // TODO: HACK: GuiTextSplit() - Review how textRows are returned to user - // textRow is an externally provided array of integers that stores row number for every splitted string - - #if !defined(RAYGUI_TEXTSPLIT_MAX_ITEMS) - #define RAYGUI_TEXTSPLIT_MAX_ITEMS 128 - #endif - #if !defined(RAYGUI_TEXTSPLIT_MAX_TEXT_SIZE) - #define RAYGUI_TEXTSPLIT_MAX_TEXT_SIZE 1024 - #endif - - static const char *result[RAYGUI_TEXTSPLIT_MAX_ITEMS] = { NULL }; // String pointers array (points to buffer data) - static char buffer[RAYGUI_TEXTSPLIT_MAX_TEXT_SIZE] = { 0 }; // Buffer data (text input copy with '\0' added) - memset(buffer, 0, RAYGUI_TEXTSPLIT_MAX_TEXT_SIZE); - - result[0] = buffer; - int counter = 1; - - if (textRow != NULL) textRow[0] = 0; - - // Count how many substrings we have on text and point to every one - for (int i = 0; i < RAYGUI_TEXTSPLIT_MAX_TEXT_SIZE; i++) - { - buffer[i] = text[i]; - if (buffer[i] == '\0') break; - else if ((buffer[i] == delimiter) || (buffer[i] == '\n')) - { - result[counter] = buffer + i + 1; - - if (textRow != NULL) - { - if (buffer[i] == '\n') textRow[counter] = textRow[counter - 1] + 1; - else textRow[counter] = textRow[counter - 1]; - } - - buffer[i] = '\0'; // Set an end of string at this point - - counter++; - if (counter > RAYGUI_TEXTSPLIT_MAX_ITEMS) break; - } - } - - *count = counter; - - return result; -} - -// Convert color data from RGB to HSV -// NOTE: Color data should be passed normalized -static Vector3 ConvertRGBtoHSV(Vector3 rgb) -{ - Vector3 hsv = { 0 }; - float min = 0.0f; - float max = 0.0f; - float delta = 0.0f; - - min = (rgb.x < rgb.y)? rgb.x : rgb.y; - min = (min < rgb.z)? min : rgb.z; - - max = (rgb.x > rgb.y)? rgb.x : rgb.y; - max = (max > rgb.z)? max : rgb.z; - - hsv.z = max; // Value - delta = max - min; - - if (delta < 0.00001f) - { - hsv.y = 0.0f; - hsv.x = 0.0f; // Undefined, maybe NAN? - return hsv; - } - - if (max > 0.0f) - { - // NOTE: If max is 0, this divide would cause a crash - hsv.y = (delta/max); // Saturation - } - else - { - // NOTE: If max is 0, then r = g = b = 0, s = 0, h is undefined - hsv.y = 0.0f; - hsv.x = 0.0f; // Undefined, maybe NAN? - return hsv; - } - - // NOTE: Comparing float values could not work properly - if (rgb.x >= max) hsv.x = (rgb.y - rgb.z)/delta; // Between yellow & magenta - else - { - if (rgb.y >= max) hsv.x = 2.0f + (rgb.z - rgb.x)/delta; // Between cyan & yellow - else hsv.x = 4.0f + (rgb.x - rgb.y)/delta; // Between magenta & cyan - } - - hsv.x *= 60.0f; // Convert to degrees - - if (hsv.x < 0.0f) hsv.x += 360.0f; - - return hsv; -} - -// Convert color data from HSV to RGB -// NOTE: Color data should be passed normalized -static Vector3 ConvertHSVtoRGB(Vector3 hsv) -{ - Vector3 rgb = { 0 }; - float hh = 0.0f, p = 0.0f, q = 0.0f, t = 0.0f, ff = 0.0f; - long i = 0; - - // NOTE: Comparing float values could not work properly - if (hsv.y <= 0.0f) - { - rgb.x = hsv.z; - rgb.y = hsv.z; - rgb.z = hsv.z; - return rgb; - } - - hh = hsv.x; - if (hh >= 360.0f) hh = 0.0f; - hh /= 60.0f; - - i = (long)hh; - ff = hh - i; - p = hsv.z*(1.0f - hsv.y); - q = hsv.z*(1.0f - (hsv.y*ff)); - t = hsv.z*(1.0f - (hsv.y*(1.0f - ff))); - - switch (i) - { - case 0: - { - rgb.x = hsv.z; - rgb.y = t; - rgb.z = p; - } break; - case 1: - { - rgb.x = q; - rgb.y = hsv.z; - rgb.z = p; - } break; - case 2: - { - rgb.x = p; - rgb.y = hsv.z; - rgb.z = t; - } break; - case 3: - { - rgb.x = p; - rgb.y = q; - rgb.z = hsv.z; - } break; - case 4: - { - rgb.x = t; - rgb.y = p; - rgb.z = hsv.z; - } break; - case 5: - default: - { - rgb.x = hsv.z; - rgb.y = p; - rgb.z = q; - } break; - } - - return rgb; -} - -// Scroll bar control (used by GuiScrollPanel()) -static int GuiScrollBar(Rectangle bounds, int value, int minValue, int maxValue) -{ - GuiState state = guiState; - - // Is the scrollbar horizontal or vertical? - bool isVertical = (bounds.width > bounds.height)? false : true; - - // The size (width or height depending on scrollbar type) of the spinner buttons - const int spinnerSize = GuiGetStyle(SCROLLBAR, ARROWS_VISIBLE)? - (isVertical? (int)bounds.width - 2*GuiGetStyle(SCROLLBAR, BORDER_WIDTH) : - (int)bounds.height - 2*GuiGetStyle(SCROLLBAR, BORDER_WIDTH)) : 0; - - // Arrow buttons [<] [>] [∧] [∨] - Rectangle arrowUpLeft = { 0 }; - Rectangle arrowDownRight = { 0 }; - - // Actual area of the scrollbar excluding the arrow buttons - Rectangle scrollbar = { 0 }; - - // Slider bar that moves --[///]----- - Rectangle slider = { 0 }; - - // Normalize value - if (value > maxValue) value = maxValue; - if (value < minValue) value = minValue; - - int valueRange = maxValue - minValue; - if (valueRange <= 0) valueRange = 1; - - int sliderSize = GuiGetStyle(SCROLLBAR, SCROLL_SLIDER_SIZE); - if (sliderSize < 1) sliderSize = 1; // TODO: Consider a minimum slider size - - // Calculate rectangles for all of the components - arrowUpLeft = RAYGUI_CLITERAL(Rectangle){ - (float)bounds.x + GuiGetStyle(SCROLLBAR, BORDER_WIDTH), - (float)bounds.y + GuiGetStyle(SCROLLBAR, BORDER_WIDTH), - (float)spinnerSize, (float)spinnerSize }; - - if (isVertical) - { - arrowDownRight = RAYGUI_CLITERAL(Rectangle){ (float)bounds.x + GuiGetStyle(SCROLLBAR, BORDER_WIDTH), (float)bounds.y + bounds.height - spinnerSize - GuiGetStyle(SCROLLBAR, BORDER_WIDTH), (float)spinnerSize, (float)spinnerSize }; - scrollbar = RAYGUI_CLITERAL(Rectangle){ bounds.x + GuiGetStyle(SCROLLBAR, BORDER_WIDTH) + GuiGetStyle(SCROLLBAR, SCROLL_PADDING), arrowUpLeft.y + arrowUpLeft.height, bounds.width - 2*(GuiGetStyle(SCROLLBAR, BORDER_WIDTH) + GuiGetStyle(SCROLLBAR, SCROLL_PADDING)), bounds.height - arrowUpLeft.height - arrowDownRight.height - 2*GuiGetStyle(SCROLLBAR, BORDER_WIDTH) }; - - // Make sure the slider won't get outside of the scrollbar - sliderSize = (sliderSize >= scrollbar.height)? ((int)scrollbar.height - 2) : sliderSize; - slider = RAYGUI_CLITERAL(Rectangle){ - bounds.x + GuiGetStyle(SCROLLBAR, BORDER_WIDTH) + GuiGetStyle(SCROLLBAR, SCROLL_SLIDER_PADDING), - scrollbar.y + (int)(((float)(value - minValue)/valueRange)*(scrollbar.height - sliderSize)), - bounds.width - 2*(GuiGetStyle(SCROLLBAR, BORDER_WIDTH) + GuiGetStyle(SCROLLBAR, SCROLL_SLIDER_PADDING)), - (float)sliderSize }; - } - else // horizontal - { - arrowDownRight = RAYGUI_CLITERAL(Rectangle){ (float)bounds.x + bounds.width - spinnerSize - GuiGetStyle(SCROLLBAR, BORDER_WIDTH), (float)bounds.y + GuiGetStyle(SCROLLBAR, BORDER_WIDTH), (float)spinnerSize, (float)spinnerSize }; - scrollbar = RAYGUI_CLITERAL(Rectangle){ arrowUpLeft.x + arrowUpLeft.width, bounds.y + GuiGetStyle(SCROLLBAR, BORDER_WIDTH) + GuiGetStyle(SCROLLBAR, SCROLL_PADDING), bounds.width - arrowUpLeft.width - arrowDownRight.width - 2*GuiGetStyle(SCROLLBAR, BORDER_WIDTH), bounds.height - 2*(GuiGetStyle(SCROLLBAR, BORDER_WIDTH) + GuiGetStyle(SCROLLBAR, SCROLL_PADDING)) }; - - // Make sure the slider won't get outside of the scrollbar - sliderSize = (sliderSize >= scrollbar.width)? ((int)scrollbar.width - 2) : sliderSize; - slider = RAYGUI_CLITERAL(Rectangle){ - scrollbar.x + (int)(((float)(value - minValue)/valueRange)*(scrollbar.width - sliderSize)), - bounds.y + GuiGetStyle(SCROLLBAR, BORDER_WIDTH) + GuiGetStyle(SCROLLBAR, SCROLL_SLIDER_PADDING), - (float)sliderSize, - bounds.height - 2*(GuiGetStyle(SCROLLBAR, BORDER_WIDTH) + GuiGetStyle(SCROLLBAR, SCROLL_SLIDER_PADDING)) }; - } - - // Update control - //-------------------------------------------------------------------- - if ((state != STATE_DISABLED) && !guiLocked) - { - Vector2 mousePoint = GetMousePosition(); - - if (guiControlExclusiveMode) // Allows to keep dragging outside of bounds - { - if (IsMouseButtonDown(MOUSE_LEFT_BUTTON) && - !CheckCollisionPointRec(mousePoint, arrowUpLeft) && - !CheckCollisionPointRec(mousePoint, arrowDownRight)) - { - if (CHECK_BOUNDS_ID(bounds, guiControlExclusiveRec)) - { - state = STATE_PRESSED; - - if (isVertical) value = (int)(((float)(mousePoint.y - scrollbar.y - slider.height/2)*valueRange)/(scrollbar.height - slider.height) + minValue); - else value = (int)(((float)(mousePoint.x - scrollbar.x - slider.width/2)*valueRange)/(scrollbar.width - slider.width) + minValue); - } - } - else - { - guiControlExclusiveMode = false; - guiControlExclusiveRec = RAYGUI_CLITERAL(Rectangle){ 0, 0, 0, 0 }; - } - } - else if (CheckCollisionPointRec(mousePoint, bounds)) - { - state = STATE_FOCUSED; - - // Handle mouse wheel - int wheel = (int)GetMouseWheelMove(); - if (wheel != 0) value += wheel; - - // Handle mouse button down - if (IsMouseButtonPressed(MOUSE_LEFT_BUTTON)) - { - guiControlExclusiveMode = true; - guiControlExclusiveRec = bounds; // Store bounds as an identifier when dragging starts - - // Check arrows click - if (CheckCollisionPointRec(mousePoint, arrowUpLeft)) value -= valueRange/GuiGetStyle(SCROLLBAR, SCROLL_SPEED); - else if (CheckCollisionPointRec(mousePoint, arrowDownRight)) value += valueRange/GuiGetStyle(SCROLLBAR, SCROLL_SPEED); - else if (!CheckCollisionPointRec(mousePoint, slider)) - { - // If click on scrollbar position but not on slider, place slider directly on that position - if (isVertical) value = (int)(((float)(mousePoint.y - scrollbar.y - slider.height/2)*valueRange)/(scrollbar.height - slider.height) + minValue); - else value = (int)(((float)(mousePoint.x - scrollbar.x - slider.width/2)*valueRange)/(scrollbar.width - slider.width) + minValue); - } - - state = STATE_PRESSED; - } - - // Keyboard control on mouse hover scrollbar - /* - if (isVertical) - { - if (IsKeyDown(KEY_DOWN)) value += 5; - else if (IsKeyDown(KEY_UP)) value -= 5; - } - else - { - if (IsKeyDown(KEY_RIGHT)) value += 5; - else if (IsKeyDown(KEY_LEFT)) value -= 5; - } - */ - } - - // Normalize value - if (value > maxValue) value = maxValue; - if (value < minValue) value = minValue; - } - //-------------------------------------------------------------------- - - // Draw control - //-------------------------------------------------------------------- - GuiDrawRectangle(bounds, GuiGetStyle(SCROLLBAR, BORDER_WIDTH), GetColor(GuiGetStyle(LISTVIEW, BORDER + state*3)), GetColor(GuiGetStyle(DEFAULT, BORDER_COLOR_DISABLED))); // Draw the background - - GuiDrawRectangle(scrollbar, 0, BLANK, GetColor(GuiGetStyle(BUTTON, BASE_COLOR_NORMAL))); // Draw the scrollbar active area background - GuiDrawRectangle(slider, 0, BLANK, GetColor(GuiGetStyle(SLIDER, BORDER + state*3))); // Draw the slider bar - - // Draw arrows (using icon if available) - if (GuiGetStyle(SCROLLBAR, ARROWS_VISIBLE)) - { -#if defined(RAYGUI_NO_ICONS) - GuiDrawText(isVertical? "^" : "<", - RAYGUI_CLITERAL(Rectangle){ arrowUpLeft.x, arrowUpLeft.y, isVertical? bounds.width : bounds.height, isVertical? bounds.width : bounds.height }, - TEXT_ALIGN_CENTER, GetColor(GuiGetStyle(DROPDOWNBOX, TEXT + (state*3)))); - GuiDrawText(isVertical? "v" : ">", - RAYGUI_CLITERAL(Rectangle){ arrowDownRight.x, arrowDownRight.y, isVertical? bounds.width : bounds.height, isVertical? bounds.width : bounds.height }, - TEXT_ALIGN_CENTER, GetColor(GuiGetStyle(DROPDOWNBOX, TEXT + (state*3)))); -#else - GuiDrawText(isVertical? "#121#" : "#118#", - RAYGUI_CLITERAL(Rectangle){ arrowUpLeft.x, arrowUpLeft.y, isVertical? bounds.width : bounds.height, isVertical? bounds.width : bounds.height }, - TEXT_ALIGN_CENTER, GetColor(GuiGetStyle(SCROLLBAR, TEXT + state*3))); // ICON_ARROW_UP_FILL / ICON_ARROW_LEFT_FILL - GuiDrawText(isVertical? "#120#" : "#119#", - RAYGUI_CLITERAL(Rectangle){ arrowDownRight.x, arrowDownRight.y, isVertical? bounds.width : bounds.height, isVertical? bounds.width : bounds.height }, - TEXT_ALIGN_CENTER, GetColor(GuiGetStyle(SCROLLBAR, TEXT + state*3))); // ICON_ARROW_DOWN_FILL / ICON_ARROW_RIGHT_FILL -#endif - } - //-------------------------------------------------------------------- - - return value; -} - -// Color fade-in or fade-out, alpha goes from 0.0f to 1.0f -// WARNING: It multiplies current alpha by alpha scale factor -static Color GuiFade(Color color, float alpha) -{ - if (alpha < 0.0f) alpha = 0.0f; - else if (alpha > 1.0f) alpha = 1.0f; - - Color result = { color.r, color.g, color.b, (unsigned char)(color.a*alpha) }; - - return result; -} - -#if defined(RAYGUI_STANDALONE) -// Returns a Color struct from hexadecimal value -static Color GetColor(int hexValue) -{ - Color color; - - color.r = (unsigned char)(hexValue >> 24) & 0xFF; - color.g = (unsigned char)(hexValue >> 16) & 0xFF; - color.b = (unsigned char)(hexValue >> 8) & 0xFF; - color.a = (unsigned char)hexValue & 0xFF; - - return color; -} - -// Returns hexadecimal value for a Color -static int ColorToInt(Color color) -{ - return (((int)color.r << 24) | ((int)color.g << 16) | ((int)color.b << 8) | (int)color.a); -} - -// Check if point is inside rectangle -static bool CheckCollisionPointRec(Vector2 point, Rectangle rec) -{ - bool collision = false; - - if ((point.x >= rec.x) && (point.x <= (rec.x + rec.width)) && - (point.y >= rec.y) && (point.y <= (rec.y + rec.height))) collision = true; - - return collision; -} - -// Formatting of text with variables to 'embed' -static const char *TextFormat(const char *text, ...) -{ - #if !defined(RAYGUI_TEXTFORMAT_MAX_SIZE) - #define RAYGUI_TEXTFORMAT_MAX_SIZE 256 - #endif - - static char buffer[RAYGUI_TEXTFORMAT_MAX_SIZE]; - - va_list args; - va_start(args, text); - vsprintf(buffer, text, args); - va_end(args); - - return buffer; -} - -// Draw rectangle with vertical gradient fill color -// NOTE: This function is only used by GuiColorPicker() -static void DrawRectangleGradientV(int posX, int posY, int width, int height, Color color1, Color color2) -{ - Rectangle bounds = { (float)posX, (float)posY, (float)width, (float)height }; - DrawRectangleGradientEx(bounds, color1, color2, color2, color1); -} - -// Split string into multiple strings -const char **TextSplit(const char *text, char delimiter, int *count) -{ - // NOTE: Current implementation returns a copy of the provided string with '\0' (string end delimiter) - // inserted between strings defined by "delimiter" parameter. No memory is dynamically allocated, - // all used memory is static... it has some limitations: - // 1. Maximum number of possible split strings is set by RAYGUI_TEXTSPLIT_MAX_ITEMS - // 2. Maximum size of text to split is RAYGUI_TEXTSPLIT_MAX_TEXT_SIZE - - #if !defined(RAYGUI_TEXTSPLIT_MAX_ITEMS) - #define RAYGUI_TEXTSPLIT_MAX_ITEMS 128 - #endif - #if !defined(RAYGUI_TEXTSPLIT_MAX_TEXT_SIZE) - #define RAYGUI_TEXTSPLIT_MAX_TEXT_SIZE 1024 - #endif - - static const char *result[RAYGUI_TEXTSPLIT_MAX_ITEMS] = { NULL }; - static char buffer[RAYGUI_TEXTSPLIT_MAX_TEXT_SIZE] = { 0 }; - memset(buffer, 0, RAYGUI_TEXTSPLIT_MAX_TEXT_SIZE); - - result[0] = buffer; - int counter = 0; - - if (text != NULL) - { - counter = 1; - - // Count how many substrings we have on text and point to every one - for (int i = 0; i < RAYGUI_TEXTSPLIT_MAX_TEXT_SIZE; i++) - { - buffer[i] = text[i]; - if (buffer[i] == '\0') break; - else if (buffer[i] == delimiter) - { - buffer[i] = '\0'; // Set an end of string at this point - result[counter] = buffer + i + 1; - counter++; - - if (counter == RAYGUI_TEXTSPLIT_MAX_ITEMS) break; - } - } - } - - *count = counter; - return result; -} - -// Get integer value from text -// NOTE: This function replaces atoi() [stdlib.h] -static int TextToInteger(const char *text) -{ - int value = 0; - int sign = 1; - - if ((text[0] == '+') || (text[0] == '-')) - { - if (text[0] == '-') sign = -1; - text++; - } - - for (int i = 0; ((text[i] >= '0') && (text[i] <= '9')); ++i) value = value*10 + (int)(text[i] - '0'); - - return value*sign; -} - -// Get float value from text -// NOTE: This function replaces atof() [stdlib.h] -// WARNING: Only '.' character is understood as decimal point -static float TextToFloat(const char *text) -{ - float value = 0.0f; - float sign = 1.0f; - - if ((text[0] == '+') || (text[0] == '-')) - { - if (text[0] == '-') sign = -1.0f; - text++; - } - - int i = 0; - for (; ((text[i] >= '0') && (text[i] <= '9')); i++) value = value*10.0f + (float)(text[i] - '0'); - - if (text[i++] != '.') value *= sign; - else - { - float divisor = 10.0f; - for (; ((text[i] >= '0') && (text[i] <= '9')); i++) - { - value += ((float)(text[i] - '0'))/divisor; - divisor = divisor*10.0f; - } - } - - return value; -} - -// Encode codepoint into UTF-8 text (char array size returned as parameter) -static const char *CodepointToUTF8(int codepoint, int *byteSize) -{ - static char utf8[6] = { 0 }; - int size = 0; - - if (codepoint <= 0x7f) - { - utf8[0] = (char)codepoint; - size = 1; - } - else if (codepoint <= 0x7ff) - { - utf8[0] = (char)(((codepoint >> 6) & 0x1f) | 0xc0); - utf8[1] = (char)((codepoint & 0x3f) | 0x80); - size = 2; - } - else if (codepoint <= 0xffff) - { - utf8[0] = (char)(((codepoint >> 12) & 0x0f) | 0xe0); - utf8[1] = (char)(((codepoint >> 6) & 0x3f) | 0x80); - utf8[2] = (char)((codepoint & 0x3f) | 0x80); - size = 3; - } - else if (codepoint <= 0x10ffff) - { - utf8[0] = (char)(((codepoint >> 18) & 0x07) | 0xf0); - utf8[1] = (char)(((codepoint >> 12) & 0x3f) | 0x80); - utf8[2] = (char)(((codepoint >> 6) & 0x3f) | 0x80); - utf8[3] = (char)((codepoint & 0x3f) | 0x80); - size = 4; - } - - *byteSize = size; - - return utf8; -} - -// Get next codepoint in a UTF-8 encoded text, scanning until '\0' is found -// When a invalid UTF-8 byte is encountered we exit as soon as possible and a '?'(0x3f) codepoint is returned -// Total number of bytes processed are returned as a parameter -// NOTE: the standard says U+FFFD should be returned in case of errors -// but that character is not supported by the default font in raylib -static int GetCodepointNext(const char *text, int *codepointSize) -{ - const char *ptr = text; - int codepoint = 0x3f; // Codepoint (defaults to '?') - *codepointSize = 1; - - // Get current codepoint and bytes processed - if (0xf0 == (0xf8 & ptr[0])) - { - // 4 byte UTF-8 codepoint - if (((ptr[1] & 0xC0) ^ 0x80) || ((ptr[2] & 0xC0) ^ 0x80) || ((ptr[3] & 0xC0) ^ 0x80)) { return codepoint; } //10xxxxxx checks - codepoint = ((0x07 & ptr[0]) << 18) | ((0x3f & ptr[1]) << 12) | ((0x3f & ptr[2]) << 6) | (0x3f & ptr[3]); - *codepointSize = 4; - } - else if (0xe0 == (0xf0 & ptr[0])) - { - // 3 byte UTF-8 codepoint */ - if (((ptr[1] & 0xC0) ^ 0x80) || ((ptr[2] & 0xC0) ^ 0x80)) { return codepoint; } //10xxxxxx checks - codepoint = ((0x0f & ptr[0]) << 12) | ((0x3f & ptr[1]) << 6) | (0x3f & ptr[2]); - *codepointSize = 3; - } - else if (0xc0 == (0xe0 & ptr[0])) - { - // 2 byte UTF-8 codepoint - if ((ptr[1] & 0xC0) ^ 0x80) { return codepoint; } //10xxxxxx checks - codepoint = ((0x1f & ptr[0]) << 6) | (0x3f & ptr[1]); - *codepointSize = 2; - } - else if (0x00 == (0x80 & ptr[0])) - { - // 1 byte UTF-8 codepoint - codepoint = ptr[0]; - *codepointSize = 1; - } - - return codepoint; -} -#endif // RAYGUI_STANDALONE - -#endif // RAYGUI_IMPLEMENTATION diff --git a/third_party/raylib/include/raylib.h b/third_party/raylib/include/raylib.h deleted file mode 100644 index ea973ff1ba..0000000000 --- a/third_party/raylib/include/raylib.h +++ /dev/null @@ -1,1766 +0,0 @@ -/********************************************************************************************** -* -* raylib v5.6-dev - A simple and easy-to-use library to enjoy videogames programming (www.raylib.com) -* -* FEATURES: -* - NO external dependencies, all required libraries included with raylib -* - Multiplatform: Windows, Linux, FreeBSD, OpenBSD, NetBSD, DragonFly, -* MacOS, Haiku, Android, Raspberry Pi, DRM native, HTML5. -* - Written in plain C code (C99) in PascalCase/camelCase notation -* - Hardware accelerated with OpenGL (1.1, 2.1, 3.3, 4.3, ES2, ES3 - choose at compile) -* - Unique OpenGL abstraction layer (usable as standalone module): [rlgl] -* - Multiple Fonts formats supported (TTF, OTF, FNT, BDF, Sprite fonts) -* - Outstanding texture formats support, including compressed formats (DXT, ETC, ASTC) -* - Full 3d support for 3d Shapes, Models, Billboards, Heightmaps and more! -* - Flexible Materials system, supporting classic maps and PBR maps -* - Animated 3D models supported (skeletal bones animation) (IQM, M3D, GLTF) -* - Shaders support, including Model shaders and Postprocessing shaders -* - Powerful math module for Vector, Matrix and Quaternion operations: [raymath] -* - Audio loading and playing with streaming support (WAV, OGG, MP3, FLAC, QOA, XM, MOD) -* - VR stereo rendering with configurable HMD device parameters -* - Bindings to multiple programming languages available! -* -* NOTES: -* - One default Font is loaded on InitWindow()->LoadFontDefault() [core, text] -* - One default Texture2D is loaded on rlglInit(), 1x1 white pixel R8G8B8A8 [rlgl] (OpenGL 3.3 or ES2) -* - One default Shader is loaded on rlglInit()->rlLoadShaderDefault() [rlgl] (OpenGL 3.3 or ES2) -* - One default RenderBatch is loaded on rlglInit()->rlLoadRenderBatch() [rlgl] (OpenGL 3.3 or ES2) -* -* DEPENDENCIES (included): -* [rcore][GLFW] rglfw (Camilla Löwy - github.com/glfw/glfw) for window/context management and input -* [rcore][RGFW] rgfw (ColleagueRiley - github.com/ColleagueRiley/RGFW) for window/context management and input -* [rlgl] glad/glad_gles2 (David Herberth - github.com/Dav1dde/glad) for OpenGL 3.3 extensions loading -* [raudio] miniaudio (David Reid - github.com/mackron/miniaudio) for audio device/context management -* -* OPTIONAL DEPENDENCIES (included): -* [rcore] msf_gif (Miles Fogle) for GIF recording -* [rcore] sinfl (Micha Mettke) for DEFLATE decompression algorithm -* [rcore] sdefl (Micha Mettke) for DEFLATE compression algorithm -* [rcore] rprand (Ramon Snatamaria) for pseudo-random numbers generation -* [rtextures] qoi (Dominic Szablewski - https://phoboslab.org) for QOI image manage -* [rtextures] stb_image (Sean Barret) for images loading (BMP, TGA, PNG, JPEG, HDR...) -* [rtextures] stb_image_write (Sean Barret) for image writing (BMP, TGA, PNG, JPG) -* [rtextures] stb_image_resize2 (Sean Barret) for image resizing algorithms -* [rtextures] stb_perlin (Sean Barret) for Perlin Noise image generation -* [rtext] stb_truetype (Sean Barret) for ttf fonts loading -* [rtext] stb_rect_pack (Sean Barret) for rectangles packing -* [rmodels] par_shapes (Philip Rideout) for parametric 3d shapes generation -* [rmodels] tinyobj_loader_c (Syoyo Fujita) for models loading (OBJ, MTL) -* [rmodels] cgltf (Johannes Kuhlmann) for models loading (glTF) -* [rmodels] m3d (bzt) for models loading (M3D, https://bztsrc.gitlab.io/model3d) -* [rmodels] vox_loader (Johann Nadalutti) for models loading (VOX) -* [raudio] dr_wav (David Reid) for WAV audio file loading -* [raudio] dr_flac (David Reid) for FLAC audio file loading -* [raudio] dr_mp3 (David Reid) for MP3 audio file loading -* [raudio] stb_vorbis (Sean Barret) for OGG audio loading -* [raudio] jar_xm (Joshua Reisenauer) for XM audio module loading -* [raudio] jar_mod (Joshua Reisenauer) for MOD audio module loading -* [raudio] qoa (Dominic Szablewski - https://phoboslab.org) for QOA audio manage -* -* -* LICENSE: zlib/libpng -* -* raylib is licensed under an unmodified zlib/libpng license, which is an OSI-certified, -* BSD-like license that allows static linking with closed source software: -* -* Copyright (c) 2013-2024 Ramon Santamaria (@raysan5) -* -* This software is provided "as-is", without any express or implied warranty. In no event -* will the authors be held liable for any damages arising from the use of this software. -* -* Permission is granted to anyone to use this software for any purpose, including commercial -* applications, and to alter it and redistribute it freely, subject to the following restrictions: -* -* 1. The origin of this software must not be misrepresented; you must not claim that you -* wrote the original software. If you use this software in a product, an acknowledgment -* in the product documentation would be appreciated but is not required. -* -* 2. Altered source versions must be plainly marked as such, and must not be misrepresented -* as being the original software. -* -* 3. This notice may not be removed or altered from any source distribution. -* -**********************************************************************************************/ - -#ifndef RAYLIB_H -#define RAYLIB_H - -#include // Required for: va_list - Only used by TraceLogCallback - -#define RAYLIB_VERSION_MAJOR 5 -#define RAYLIB_VERSION_MINOR 6 -#define RAYLIB_VERSION_PATCH 0 -#define RAYLIB_VERSION "5.6-dev" - -// Function specifiers in case library is build/used as a shared library -// NOTE: Microsoft specifiers to tell compiler that symbols are imported/exported from a .dll -// NOTE: visibility("default") attribute makes symbols "visible" when compiled with -fvisibility=hidden -#if defined(_WIN32) - #if defined(__TINYC__) - #define __declspec(x) __attribute__((x)) - #endif - #if defined(BUILD_LIBTYPE_SHARED) - #define RLAPI __declspec(dllexport) // We are building the library as a Win32 shared library (.dll) - #elif defined(USE_LIBTYPE_SHARED) - #define RLAPI __declspec(dllimport) // We are using the library as a Win32 shared library (.dll) - #endif -#else - #if defined(BUILD_LIBTYPE_SHARED) - #define RLAPI __attribute__((visibility("default"))) // We are building as a Unix shared library (.so/.dylib) - #endif -#endif - -#ifndef RLAPI - #define RLAPI // Functions defined as 'extern' by default (implicit specifiers) -#endif - -//---------------------------------------------------------------------------------- -// Some basic Defines -//---------------------------------------------------------------------------------- -#ifndef PI - #define PI 3.14159265358979323846f -#endif -#ifndef DEG2RAD - #define DEG2RAD (PI/180.0f) -#endif -#ifndef RAD2DEG - #define RAD2DEG (180.0f/PI) -#endif - -// Allow custom memory allocators -// NOTE: Require recompiling raylib sources -#ifndef RL_MALLOC - #define RL_MALLOC(sz) malloc(sz) -#endif -#ifndef RL_CALLOC - #define RL_CALLOC(n,sz) calloc(n,sz) -#endif -#ifndef RL_REALLOC - #define RL_REALLOC(ptr,sz) realloc(ptr,sz) -#endif -#ifndef RL_FREE - #define RL_FREE(ptr) free(ptr) -#endif - -// NOTE: MSVC C++ compiler does not support compound literals (C99 feature) -// Plain structures in C++ (without constructors) can be initialized with { } -// This is called aggregate initialization (C++11 feature) -#if defined(__cplusplus) - #define CLITERAL(type) type -#else - #define CLITERAL(type) (type) -#endif - -// Some compilers (mostly macos clang) default to C++98, -// where aggregate initialization can't be used -// So, give a more clear error stating how to fix this -#if !defined(_MSC_VER) && (defined(__cplusplus) && __cplusplus < 201103L) - #error "C++11 or later is required. Add -std=c++11" -#endif - -// NOTE: We set some defines with some data types declared by raylib -// Other modules (raymath, rlgl) also require some of those types, so, -// to be able to use those other modules as standalone (not depending on raylib) -// this defines are very useful for internal check and avoid type (re)definitions -#define RL_COLOR_TYPE -#define RL_RECTANGLE_TYPE -#define RL_VECTOR2_TYPE -#define RL_VECTOR3_TYPE -#define RL_VECTOR4_TYPE -#define RL_QUATERNION_TYPE -#define RL_MATRIX_TYPE - -// Some Basic Colors -// NOTE: Custom raylib color palette for amazing visuals on WHITE background -#define _rl_LIGHTGRAY CLITERAL(Color){ 200, 200, 200, 255 } // Light Gray -#define _rl_GRAY CLITERAL(Color){ 130, 130, 130, 255 } // Gray -#define _rl_DARKGRAY CLITERAL(Color){ 80, 80, 80, 255 } // Dark Gray -#define _rl_YELLOW CLITERAL(Color){ 253, 249, 0, 255 } // Yellow -#define _rl_GOLD CLITERAL(Color){ 255, 203, 0, 255 } // Gold -#define _rl_ORANGE CLITERAL(Color){ 255, 161, 0, 255 } // Orange -#define _rl_PINK CLITERAL(Color){ 255, 109, 194, 255 } // Pink -#define _rl_RED CLITERAL(Color){ 230, 41, 55, 255 } // Red -#define _rl_MAROON CLITERAL(Color){ 190, 33, 55, 255 } // Maroon -#define _rl_GREEN CLITERAL(Color){ 0, 228, 48, 255 } // Green -#define _rl_LIME CLITERAL(Color){ 0, 158, 47, 255 } // Lime -#define _rl_DARKGREEN CLITERAL(Color){ 0, 117, 44, 255 } // Dark Green -#define _rl_SKYBLUE CLITERAL(Color){ 102, 191, 255, 255 } // Sky Blue -#define _rl_BLUE CLITERAL(Color){ 0, 121, 241, 255 } // Blue -#define _rl_DARKBLUE CLITERAL(Color){ 0, 82, 172, 255 } // Dark Blue -#define _rl_PURPLE CLITERAL(Color){ 200, 122, 255, 255 } // Purple -#define _rl_VIOLET CLITERAL(Color){ 135, 60, 190, 255 } // Violet -#define _rl_DARKPURPLE CLITERAL(Color){ 112, 31, 126, 255 } // Dark Purple -#define _rl_BEIGE CLITERAL(Color){ 211, 176, 131, 255 } // Beige -#define _rl_BROWN CLITERAL(Color){ 127, 106, 79, 255 } // Brown -#define _rl_DARKBROWN CLITERAL(Color){ 76, 63, 47, 255 } // Dark Brown - -#define _rl_WHITE CLITERAL(Color){ 255, 255, 255, 255 } // White -#define _rl_BLACK CLITERAL(Color){ 0, 0, 0, 255 } // Black -#define _rl_BLANK CLITERAL(Color){ 0, 0, 0, 0 } // Blank (Transparent) -#define _rl_MAGENTA CLITERAL(Color){ 255, 0, 255, 255 } // Magenta -#define _rl_RAYWHITE CLITERAL(Color){ 245, 245, 245, 255 } // My own White (raylib logo) - -#ifndef OPENPILOT_RAYLIB - #define LIGHTGRAY _rl_LIGHTGRAY - #define GRAY _rl_GRAY - #define DARKGRAY _rl_DARKGRAY - #define YELLOW _rl_YELLOW - #define GOLD _rl_GOLD - #define ORANGE _rl_ORANGE - #define PINK _rl_PINK - #define RED _rl_RED - #define MAROON _rl_MAROON - #define GREEN _rl_GREEN - #define LIME _rl_LIME - #define DARKGREEN _rl_DARKGREEN - #define SKYBLUE _rl_SKYBLUE - #define BLUE _rl_BLUE - #define DARKBLUE _rl_DARKBLUE - #define PURPLE _rl_PURPLE - #define VIOLET _rl_VIOLET - #define DARKPURPLE _rl_DARKBLUE - #define BEIGE _rl_BEIGE - #define BROWN _rl_BROWN - #define DARKBROWN _rl_DARKBROWN - - #define WHITE _rl_WHITE - #define BLACK _rl_BLACK - #define BLANK _rl_BLANK - #define MAGENTA _rl_MAGENTA - #define RAYWHITE _rl_RAYWHITE -#else - #define RAYLIB_LIGHTGRAY _rl_LIGHTGRAY - #define RAYLIB_GRAY _rl_GRAY - #define RAYLIB_DARKGRAY _rl_DARKGRAY - #define RAYLIB_YELLOW _rl_YELLOW - #define RAYLIB_GOLD _rl_GOLD - #define RAYLIB_ORANGE _rl_ORANGE - #define RAYLIB_PINK _rl_PINK - #define RAYLIB_RED _rl_RED - #define RAYLIB_MAROON _rl_MAROON - #define RAYLIB_GREEN _rl_GREEN - #define RAYLIB_LIME _rl_LIME - #define RAYLIB_DARKGREEN _rl_DARKGREEN - #define RAYLIB_SKYBLUE _rl_SKYBLUE - #define RAYLIB_BLUE _rl_BLUE - #define RAYLIB_DARKBLUE _rl_DARKBLUE - #define RAYLIB_PURPLE _rl_PURPLE - #define RAYLIB_VIOLET _rl_VIOLET - #define RAYLIB_DARKPURPLE _rl_DARKBLUE - #define RAYLIB_BEIGE _rl_BEIGE - #define RAYLIB_BROWN _rl_BROWN - #define RAYLIB_DARKBROWN _rl_DARKBROWN - - #define RAYLIB_WHITE _rl_WHITE - #define RAYLIB_BLACK _rl_BLACK - #define RAYLIB_BLANK _rl_BLANK - #define RAYLIB_MAGENTA _rl_MAGENTA - #define RAYLIB_RAYWHITE _rl_RAYWHITE -#endif - -//---------------------------------------------------------------------------------- -// Structures Definition -//---------------------------------------------------------------------------------- -// Boolean type -#if (defined(__STDC__) && __STDC_VERSION__ >= 199901L) || (defined(_MSC_VER) && _MSC_VER >= 1800) - #include -#elif !defined(__cplusplus) && !defined(bool) - typedef enum bool { false = 0, true = !false } bool; - #define RL_BOOL_TYPE -#endif - -// Vector2, 2 components -typedef struct Vector2 { - float x; // Vector x component - float y; // Vector y component -} Vector2; - -// Vector3, 3 components -typedef struct Vector3 { - float x; // Vector x component - float y; // Vector y component - float z; // Vector z component -} Vector3; - -// Vector4, 4 components -typedef struct Vector4 { - float x; // Vector x component - float y; // Vector y component - float z; // Vector z component - float w; // Vector w component -} Vector4; - -// Quaternion, 4 components (Vector4 alias) -typedef Vector4 Quaternion; - -// Matrix, 4x4 components, column major, OpenGL style, right-handed -typedef struct Matrix { - float m0, m4, m8, m12; // Matrix first row (4 components) - float m1, m5, m9, m13; // Matrix second row (4 components) - float m2, m6, m10, m14; // Matrix third row (4 components) - float m3, m7, m11, m15; // Matrix fourth row (4 components) -} Matrix; - -// Color, 4 components, R8G8B8A8 (32bit) -typedef struct Color { - unsigned char r; // Color red value - unsigned char g; // Color green value - unsigned char b; // Color blue value - unsigned char a; // Color alpha value -} Color; - -// Rectangle, 4 components -typedef struct Rectangle { - float x; // Rectangle top-left corner position x - float y; // Rectangle top-left corner position y - float width; // Rectangle width - float height; // Rectangle height -} Rectangle; - -// Image, pixel data stored in CPU memory (RAM) -typedef struct Image { - void *data; // Image raw data - int width; // Image base width - int height; // Image base height - int mipmaps; // Mipmap levels, 1 by default - int format; // Data format (PixelFormat type) -} Image; - -// Texture, tex data stored in GPU memory (VRAM) -typedef struct Texture { - unsigned int id; // OpenGL texture id - int width; // Texture base width - int height; // Texture base height - int mipmaps; // Mipmap levels, 1 by default - int format; // Data format (PixelFormat type) -} Texture; - -// Texture2D, same as Texture -typedef Texture Texture2D; - -// TextureCubemap, same as Texture -typedef Texture TextureCubemap; - -// RenderTexture, fbo for texture rendering -typedef struct RenderTexture { - unsigned int id; // OpenGL framebuffer object id - Texture texture; // Color buffer attachment texture - Texture depth; // Depth buffer attachment texture -} RenderTexture; - -// RenderTexture2D, same as RenderTexture -typedef RenderTexture RenderTexture2D; - -// NPatchInfo, n-patch layout info -typedef struct NPatchInfo { - Rectangle source; // Texture source rectangle - int left; // Left border offset - int top; // Top border offset - int right; // Right border offset - int bottom; // Bottom border offset - int layout; // Layout of the n-patch: 3x3, 1x3 or 3x1 -} NPatchInfo; - -// GlyphInfo, font characters glyphs info -typedef struct GlyphInfo { - int value; // Character value (Unicode) - int offsetX; // Character offset X when drawing - int offsetY; // Character offset Y when drawing - int advanceX; // Character advance position X - Image image; // Character image data -} GlyphInfo; - -// Font, font texture and GlyphInfo array data -typedef struct Font { - int baseSize; // Base size (default chars height) - int glyphCount; // Number of glyph characters - int glyphPadding; // Padding around the glyph characters - Texture2D texture; // Texture atlas containing the glyphs - Rectangle *recs; // Rectangles in texture for the glyphs - GlyphInfo *glyphs; // Glyphs info data -} Font; - -// Camera, defines position/orientation in 3d space -typedef struct Camera3D { - Vector3 position; // Camera position - Vector3 target; // Camera target it looks-at - Vector3 up; // Camera up vector (rotation over its axis) - float fovy; // Camera field-of-view aperture in Y (degrees) in perspective, used as near plane width in orthographic - int projection; // Camera projection: CAMERA_PERSPECTIVE or CAMERA_ORTHOGRAPHIC -} Camera3D; - -typedef Camera3D Camera; // Camera type fallback, defaults to Camera3D - -// Camera2D, defines position/orientation in 2d space -typedef struct Camera2D { - Vector2 offset; // Camera offset (displacement from target) - Vector2 target; // Camera target (rotation and zoom origin) - float rotation; // Camera rotation in degrees - float zoom; // Camera zoom (scaling), should be 1.0f by default -} Camera2D; - -// Mesh, vertex data and vao/vbo -typedef struct Mesh { - int vertexCount; // Number of vertices stored in arrays - int triangleCount; // Number of triangles stored (indexed or not) - - // Vertex attributes data - float *vertices; // Vertex position (XYZ - 3 components per vertex) (shader-location = 0) - float *texcoords; // Vertex texture coordinates (UV - 2 components per vertex) (shader-location = 1) - float *texcoords2; // Vertex texture second coordinates (UV - 2 components per vertex) (shader-location = 5) - float *normals; // Vertex normals (XYZ - 3 components per vertex) (shader-location = 2) - float *tangents; // Vertex tangents (XYZW - 4 components per vertex) (shader-location = 4) - unsigned char *colors; // Vertex colors (RGBA - 4 components per vertex) (shader-location = 3) - unsigned short *indices; // Vertex indices (in case vertex data comes indexed) - - // Animation vertex data - float *animVertices; // Animated vertex positions (after bones transformations) - float *animNormals; // Animated normals (after bones transformations) - unsigned char *boneIds; // Vertex bone ids, max 255 bone ids, up to 4 bones influence by vertex (skinning) (shader-location = 6) - float *boneWeights; // Vertex bone weight, up to 4 bones influence by vertex (skinning) (shader-location = 7) - Matrix *boneMatrices; // Bones animated transformation matrices - int boneCount; // Number of bones - - // OpenGL identifiers - unsigned int vaoId; // OpenGL Vertex Array Object id - unsigned int *vboId; // OpenGL Vertex Buffer Objects id (default vertex data) -} Mesh; - -// Shader -typedef struct Shader { - unsigned int id; // Shader program id - int *locs; // Shader locations array (RL_MAX_SHADER_LOCATIONS) -} Shader; - -// MaterialMap -typedef struct MaterialMap { - Texture2D texture; // Material map texture - Color color; // Material map color - float value; // Material map value -} MaterialMap; - -// Material, includes shader and maps -typedef struct Material { - Shader shader; // Material shader - MaterialMap *maps; // Material maps array (MAX_MATERIAL_MAPS) - float params[4]; // Material generic parameters (if required) -} Material; - -// Transform, vertex transformation data -typedef struct Transform { - Vector3 translation; // Translation - Quaternion rotation; // Rotation - Vector3 scale; // Scale -} Transform; - -// Bone, skeletal animation bone -typedef struct BoneInfo { - char name[32]; // Bone name - int parent; // Bone parent -} BoneInfo; - -// Model, meshes, materials and animation data -typedef struct Model { - Matrix transform; // Local transform matrix - - int meshCount; // Number of meshes - int materialCount; // Number of materials - Mesh *meshes; // Meshes array - Material *materials; // Materials array - int *meshMaterial; // Mesh material number - - // Animation data - int boneCount; // Number of bones - BoneInfo *bones; // Bones information (skeleton) - Transform *bindPose; // Bones base transformation (pose) -} Model; - -// ModelAnimation -typedef struct ModelAnimation { - int boneCount; // Number of bones - int frameCount; // Number of animation frames - BoneInfo *bones; // Bones information (skeleton) - Transform **framePoses; // Poses array by frame - char name[32]; // Animation name -} ModelAnimation; - -// Ray, ray for raycasting -typedef struct Ray { - Vector3 position; // Ray position (origin) - Vector3 direction; // Ray direction (normalized) -} Ray; - -// RayCollision, ray hit information -typedef struct RayCollision { - bool hit; // Did the ray hit something? - float distance; // Distance to the nearest hit - Vector3 point; // Point of the nearest hit - Vector3 normal; // Surface normal of hit -} RayCollision; - -// BoundingBox -typedef struct BoundingBox { - Vector3 min; // Minimum vertex box-corner - Vector3 max; // Maximum vertex box-corner -} BoundingBox; - -// Wave, audio wave data -typedef struct Wave { - unsigned int frameCount; // Total number of frames (considering channels) - unsigned int sampleRate; // Frequency (samples per second) - unsigned int sampleSize; // Bit depth (bits per sample): 8, 16, 32 (24 not supported) - unsigned int channels; // Number of channels (1-mono, 2-stereo, ...) - void *data; // Buffer data pointer -} Wave; - -// Opaque structs declaration -// NOTE: Actual structs are defined internally in raudio module -typedef struct rAudioBuffer rAudioBuffer; -typedef struct rAudioProcessor rAudioProcessor; - -// AudioStream, custom audio stream -typedef struct AudioStream { - rAudioBuffer *buffer; // Pointer to internal data used by the audio system - rAudioProcessor *processor; // Pointer to internal data processor, useful for audio effects - - unsigned int sampleRate; // Frequency (samples per second) - unsigned int sampleSize; // Bit depth (bits per sample): 8, 16, 32 (24 not supported) - unsigned int channels; // Number of channels (1-mono, 2-stereo, ...) -} AudioStream; - -// Sound -typedef struct Sound { - AudioStream stream; // Audio stream - unsigned int frameCount; // Total number of frames (considering channels) -} Sound; - -// Music, audio stream, anything longer than ~10 seconds should be streamed -typedef struct Music { - AudioStream stream; // Audio stream - unsigned int frameCount; // Total number of frames (considering channels) - bool looping; // Music looping enable - - int ctxType; // Type of music context (audio filetype) - void *ctxData; // Audio context data, depends on type -} Music; - -// VrDeviceInfo, Head-Mounted-Display device parameters -typedef struct VrDeviceInfo { - int hResolution; // Horizontal resolution in pixels - int vResolution; // Vertical resolution in pixels - float hScreenSize; // Horizontal size in meters - float vScreenSize; // Vertical size in meters - float eyeToScreenDistance; // Distance between eye and display in meters - float lensSeparationDistance; // Lens separation distance in meters - float interpupillaryDistance; // IPD (distance between pupils) in meters - float lensDistortionValues[4]; // Lens distortion constant parameters - float chromaAbCorrection[4]; // Chromatic aberration correction parameters -} VrDeviceInfo; - -// VrStereoConfig, VR stereo rendering configuration for simulator -typedef struct VrStereoConfig { - Matrix projection[2]; // VR projection matrices (per eye) - Matrix viewOffset[2]; // VR view offset matrices (per eye) - float leftLensCenter[2]; // VR left lens center - float rightLensCenter[2]; // VR right lens center - float leftScreenCenter[2]; // VR left screen center - float rightScreenCenter[2]; // VR right screen center - float scale[2]; // VR distortion scale - float scaleIn[2]; // VR distortion scale in -} VrStereoConfig; - -// File path list -typedef struct FilePathList { - unsigned int capacity; // Filepaths max entries - unsigned int count; // Filepaths entries count - char **paths; // Filepaths entries -} FilePathList; - -// Automation event -typedef struct AutomationEvent { - unsigned int frame; // Event frame - unsigned int type; // Event type (AutomationEventType) - int params[4]; // Event parameters (if required) -} AutomationEvent; - -// Automation event list -typedef struct AutomationEventList { - unsigned int capacity; // Events max entries (MAX_AUTOMATION_EVENTS) - unsigned int count; // Events entries count - AutomationEvent *events; // Events entries -} AutomationEventList; - -//---------------------------------------------------------------------------------- -// Enumerators Definition -//---------------------------------------------------------------------------------- -// System/Window config flags -// NOTE: Every bit registers one state (use it with bit masks) -// By default all flags are set to 0 -typedef enum { - FLAG_VSYNC_HINT = 0x00000040, // Set to try enabling V-Sync on GPU - FLAG_FULLSCREEN_MODE = 0x00000002, // Set to run program in fullscreen - FLAG_WINDOW_RESIZABLE = 0x00000004, // Set to allow resizable window - FLAG_WINDOW_UNDECORATED = 0x00000008, // Set to disable window decoration (frame and buttons) - FLAG_WINDOW_HIDDEN = 0x00000080, // Set to hide window - FLAG_WINDOW_MINIMIZED = 0x00000200, // Set to minimize window (iconify) - FLAG_WINDOW_MAXIMIZED = 0x00000400, // Set to maximize window (expanded to monitor) - FLAG_WINDOW_UNFOCUSED = 0x00000800, // Set to window non focused - FLAG_WINDOW_TOPMOST = 0x00001000, // Set to window always on top - FLAG_WINDOW_ALWAYS_RUN = 0x00000100, // Set to allow windows running while minimized - FLAG_WINDOW_TRANSPARENT = 0x00000010, // Set to allow transparent framebuffer - FLAG_WINDOW_HIGHDPI = 0x00002000, // Set to support HighDPI - FLAG_WINDOW_MOUSE_PASSTHROUGH = 0x00004000, // Set to support mouse passthrough, only supported when FLAG_WINDOW_UNDECORATED - FLAG_BORDERLESS_WINDOWED_MODE = 0x00008000, // Set to run program in borderless windowed mode - FLAG_MSAA_4X_HINT = 0x00000020, // Set to try enabling MSAA 4X - FLAG_INTERLACED_HINT = 0x00010000 // Set to try enabling interlaced video format (for V3D) -} ConfigFlags; - -// Trace log level -// NOTE: Organized by priority level -typedef enum { - LOG_ALL = 0, // Display all logs - LOG_TRACE, // Trace logging, intended for internal use only - LOG_DEBUG, // Debug logging, used for internal debugging, it should be disabled on release builds - LOG_INFO, // Info logging, used for program execution info - LOG_WARNING, // Warning logging, used on recoverable failures - LOG_ERROR, // Error logging, used on unrecoverable failures - LOG_FATAL, // Fatal logging, used to abort program: exit(EXIT_FAILURE) - LOG_NONE // Disable logging -} TraceLogLevel; - -// Keyboard keys (US keyboard layout) -// NOTE: Use GetKeyPressed() to allow redefining -// required keys for alternative layouts -typedef enum { - KEY_NULL = 0, // Key: NULL, used for no key pressed - // Alphanumeric keys - KEY_APOSTROPHE = 39, // Key: ' - KEY_COMMA = 44, // Key: , - KEY_MINUS = 45, // Key: - - KEY_PERIOD = 46, // Key: . - KEY_SLASH = 47, // Key: / - KEY_ZERO = 48, // Key: 0 - KEY_ONE = 49, // Key: 1 - KEY_TWO = 50, // Key: 2 - KEY_THREE = 51, // Key: 3 - KEY_FOUR = 52, // Key: 4 - KEY_FIVE = 53, // Key: 5 - KEY_SIX = 54, // Key: 6 - KEY_SEVEN = 55, // Key: 7 - KEY_EIGHT = 56, // Key: 8 - KEY_NINE = 57, // Key: 9 - KEY_SEMICOLON = 59, // Key: ; - KEY_EQUAL = 61, // Key: = - KEY_A = 65, // Key: A | a - KEY_B = 66, // Key: B | b - KEY_C = 67, // Key: C | c - KEY_D = 68, // Key: D | d - KEY_E = 69, // Key: E | e - KEY_F = 70, // Key: F | f - KEY_G = 71, // Key: G | g - KEY_H = 72, // Key: H | h - KEY_I = 73, // Key: I | i - KEY_J = 74, // Key: J | j - KEY_K = 75, // Key: K | k - KEY_L = 76, // Key: L | l - KEY_M = 77, // Key: M | m - KEY_N = 78, // Key: N | n - KEY_O = 79, // Key: O | o - KEY_P = 80, // Key: P | p - KEY_Q = 81, // Key: Q | q - KEY_R = 82, // Key: R | r - KEY_S = 83, // Key: S | s - KEY_T = 84, // Key: T | t - KEY_U = 85, // Key: U | u - KEY_V = 86, // Key: V | v - KEY_W = 87, // Key: W | w - KEY_X = 88, // Key: X | x - KEY_Y = 89, // Key: Y | y - KEY_Z = 90, // Key: Z | z - KEY_LEFT_BRACKET = 91, // Key: [ - KEY_BACKSLASH = 92, // Key: '\' - KEY_RIGHT_BRACKET = 93, // Key: ] - KEY_GRAVE = 96, // Key: ` - // Function keys - KEY_SPACE = 32, // Key: Space - KEY_ESCAPE = 256, // Key: Esc - KEY_ENTER = 257, // Key: Enter - KEY_TAB = 258, // Key: Tab - KEY_BACKSPACE = 259, // Key: Backspace - KEY_INSERT = 260, // Key: Ins - KEY_DELETE = 261, // Key: Del - KEY_RIGHT = 262, // Key: Cursor right - KEY_LEFT = 263, // Key: Cursor left - KEY_DOWN = 264, // Key: Cursor down - KEY_UP = 265, // Key: Cursor up - KEY_PAGE_UP = 266, // Key: Page up - KEY_PAGE_DOWN = 267, // Key: Page down - KEY_HOME = 268, // Key: Home - KEY_END = 269, // Key: End - KEY_CAPS_LOCK = 280, // Key: Caps lock - KEY_SCROLL_LOCK = 281, // Key: Scroll down - KEY_NUM_LOCK = 282, // Key: Num lock - KEY_PRINT_SCREEN = 283, // Key: Print screen - KEY_PAUSE = 284, // Key: Pause - KEY_F1 = 290, // Key: F1 - KEY_F2 = 291, // Key: F2 - KEY_F3 = 292, // Key: F3 - KEY_F4 = 293, // Key: F4 - KEY_F5 = 294, // Key: F5 - KEY_F6 = 295, // Key: F6 - KEY_F7 = 296, // Key: F7 - KEY_F8 = 297, // Key: F8 - KEY_F9 = 298, // Key: F9 - KEY_F10 = 299, // Key: F10 - KEY_F11 = 300, // Key: F11 - KEY_F12 = 301, // Key: F12 - KEY_LEFT_SHIFT = 340, // Key: Shift left - KEY_LEFT_CONTROL = 341, // Key: Control left - KEY_LEFT_ALT = 342, // Key: Alt left - KEY_LEFT_SUPER = 343, // Key: Super left - KEY_RIGHT_SHIFT = 344, // Key: Shift right - KEY_RIGHT_CONTROL = 345, // Key: Control right - KEY_RIGHT_ALT = 346, // Key: Alt right - KEY_RIGHT_SUPER = 347, // Key: Super right - KEY_KB_MENU = 348, // Key: KB menu - // Keypad keys - KEY_KP_0 = 320, // Key: Keypad 0 - KEY_KP_1 = 321, // Key: Keypad 1 - KEY_KP_2 = 322, // Key: Keypad 2 - KEY_KP_3 = 323, // Key: Keypad 3 - KEY_KP_4 = 324, // Key: Keypad 4 - KEY_KP_5 = 325, // Key: Keypad 5 - KEY_KP_6 = 326, // Key: Keypad 6 - KEY_KP_7 = 327, // Key: Keypad 7 - KEY_KP_8 = 328, // Key: Keypad 8 - KEY_KP_9 = 329, // Key: Keypad 9 - KEY_KP_DECIMAL = 330, // Key: Keypad . - KEY_KP_DIVIDE = 331, // Key: Keypad / - KEY_KP_MULTIPLY = 332, // Key: Keypad * - KEY_KP_SUBTRACT = 333, // Key: Keypad - - KEY_KP_ADD = 334, // Key: Keypad + - KEY_KP_ENTER = 335, // Key: Keypad Enter - KEY_KP_EQUAL = 336, // Key: Keypad = - // Android key buttons - KEY_BACK = 4, // Key: Android back button - KEY_MENU = 5, // Key: Android menu button - KEY_VOLUME_UP = 24, // Key: Android volume up button - KEY_VOLUME_DOWN = 25 // Key: Android volume down button -} KeyboardKey; - -// Add backwards compatibility support for deprecated names -#define MOUSE_LEFT_BUTTON MOUSE_BUTTON_LEFT -#define MOUSE_RIGHT_BUTTON MOUSE_BUTTON_RIGHT -#define MOUSE_MIDDLE_BUTTON MOUSE_BUTTON_MIDDLE - -// Mouse buttons -typedef enum { - MOUSE_BUTTON_LEFT = 0, // Mouse button left - MOUSE_BUTTON_RIGHT = 1, // Mouse button right - MOUSE_BUTTON_MIDDLE = 2, // Mouse button middle (pressed wheel) - MOUSE_BUTTON_SIDE = 3, // Mouse button side (advanced mouse device) - MOUSE_BUTTON_EXTRA = 4, // Mouse button extra (advanced mouse device) - MOUSE_BUTTON_FORWARD = 5, // Mouse button forward (advanced mouse device) - MOUSE_BUTTON_BACK = 6, // Mouse button back (advanced mouse device) -} MouseButton; - -// Mouse cursor -typedef enum { - MOUSE_CURSOR_DEFAULT = 0, // Default pointer shape - MOUSE_CURSOR_ARROW = 1, // Arrow shape - MOUSE_CURSOR_IBEAM = 2, // Text writing cursor shape - MOUSE_CURSOR_CROSSHAIR = 3, // Cross shape - MOUSE_CURSOR_POINTING_HAND = 4, // Pointing hand cursor - MOUSE_CURSOR_RESIZE_EW = 5, // Horizontal resize/move arrow shape - MOUSE_CURSOR_RESIZE_NS = 6, // Vertical resize/move arrow shape - MOUSE_CURSOR_RESIZE_NWSE = 7, // Top-left to bottom-right diagonal resize/move arrow shape - MOUSE_CURSOR_RESIZE_NESW = 8, // The top-right to bottom-left diagonal resize/move arrow shape - MOUSE_CURSOR_RESIZE_ALL = 9, // The omnidirectional resize/move cursor shape - MOUSE_CURSOR_NOT_ALLOWED = 10 // The operation-not-allowed shape -} MouseCursor; - -// Gamepad buttons -typedef enum { - GAMEPAD_BUTTON_UNKNOWN = 0, // Unknown button, just for error checking - GAMEPAD_BUTTON_LEFT_FACE_UP, // Gamepad left DPAD up button - GAMEPAD_BUTTON_LEFT_FACE_RIGHT, // Gamepad left DPAD right button - GAMEPAD_BUTTON_LEFT_FACE_DOWN, // Gamepad left DPAD down button - GAMEPAD_BUTTON_LEFT_FACE_LEFT, // Gamepad left DPAD left button - GAMEPAD_BUTTON_RIGHT_FACE_UP, // Gamepad right button up (i.e. PS3: Triangle, Xbox: Y) - GAMEPAD_BUTTON_RIGHT_FACE_RIGHT, // Gamepad right button right (i.e. PS3: Circle, Xbox: B) - GAMEPAD_BUTTON_RIGHT_FACE_DOWN, // Gamepad right button down (i.e. PS3: Cross, Xbox: A) - GAMEPAD_BUTTON_RIGHT_FACE_LEFT, // Gamepad right button left (i.e. PS3: Square, Xbox: X) - GAMEPAD_BUTTON_LEFT_TRIGGER_1, // Gamepad top/back trigger left (first), it could be a trailing button - GAMEPAD_BUTTON_LEFT_TRIGGER_2, // Gamepad top/back trigger left (second), it could be a trailing button - GAMEPAD_BUTTON_RIGHT_TRIGGER_1, // Gamepad top/back trigger right (first), it could be a trailing button - GAMEPAD_BUTTON_RIGHT_TRIGGER_2, // Gamepad top/back trigger right (second), it could be a trailing button - GAMEPAD_BUTTON_MIDDLE_LEFT, // Gamepad center buttons, left one (i.e. PS3: Select) - GAMEPAD_BUTTON_MIDDLE, // Gamepad center buttons, middle one (i.e. PS3: PS, Xbox: XBOX) - GAMEPAD_BUTTON_MIDDLE_RIGHT, // Gamepad center buttons, right one (i.e. PS3: Start) - GAMEPAD_BUTTON_LEFT_THUMB, // Gamepad joystick pressed button left - GAMEPAD_BUTTON_RIGHT_THUMB // Gamepad joystick pressed button right -} GamepadButton; - -// Gamepad axis -typedef enum { - GAMEPAD_AXIS_LEFT_X = 0, // Gamepad left stick X axis - GAMEPAD_AXIS_LEFT_Y = 1, // Gamepad left stick Y axis - GAMEPAD_AXIS_RIGHT_X = 2, // Gamepad right stick X axis - GAMEPAD_AXIS_RIGHT_Y = 3, // Gamepad right stick Y axis - GAMEPAD_AXIS_LEFT_TRIGGER = 4, // Gamepad back trigger left, pressure level: [1..-1] - GAMEPAD_AXIS_RIGHT_TRIGGER = 5 // Gamepad back trigger right, pressure level: [1..-1] -} GamepadAxis; - -// Material map index -typedef enum { - MATERIAL_MAP_ALBEDO = 0, // Albedo material (same as: MATERIAL_MAP_DIFFUSE) - MATERIAL_MAP_METALNESS, // Metalness material (same as: MATERIAL_MAP_SPECULAR) - MATERIAL_MAP_NORMAL, // Normal material - MATERIAL_MAP_ROUGHNESS, // Roughness material - MATERIAL_MAP_OCCLUSION, // Ambient occlusion material - MATERIAL_MAP_EMISSION, // Emission material - MATERIAL_MAP_HEIGHT, // Heightmap material - MATERIAL_MAP_CUBEMAP, // Cubemap material (NOTE: Uses GL_TEXTURE_CUBE_MAP) - MATERIAL_MAP_IRRADIANCE, // Irradiance material (NOTE: Uses GL_TEXTURE_CUBE_MAP) - MATERIAL_MAP_PREFILTER, // Prefilter material (NOTE: Uses GL_TEXTURE_CUBE_MAP) - MATERIAL_MAP_BRDF // Brdf material -} MaterialMapIndex; - -#define MATERIAL_MAP_DIFFUSE MATERIAL_MAP_ALBEDO -#define MATERIAL_MAP_SPECULAR MATERIAL_MAP_METALNESS - -// Shader location index -typedef enum { - SHADER_LOC_VERTEX_POSITION = 0, // Shader location: vertex attribute: position - SHADER_LOC_VERTEX_TEXCOORD01, // Shader location: vertex attribute: texcoord01 - SHADER_LOC_VERTEX_TEXCOORD02, // Shader location: vertex attribute: texcoord02 - SHADER_LOC_VERTEX_NORMAL, // Shader location: vertex attribute: normal - SHADER_LOC_VERTEX_TANGENT, // Shader location: vertex attribute: tangent - SHADER_LOC_VERTEX_COLOR, // Shader location: vertex attribute: color - SHADER_LOC_MATRIX_MVP, // Shader location: matrix uniform: model-view-projection - SHADER_LOC_MATRIX_VIEW, // Shader location: matrix uniform: view (camera transform) - SHADER_LOC_MATRIX_PROJECTION, // Shader location: matrix uniform: projection - SHADER_LOC_MATRIX_MODEL, // Shader location: matrix uniform: model (transform) - SHADER_LOC_MATRIX_NORMAL, // Shader location: matrix uniform: normal - SHADER_LOC_VECTOR_VIEW, // Shader location: vector uniform: view - SHADER_LOC_COLOR_DIFFUSE, // Shader location: vector uniform: diffuse color - SHADER_LOC_COLOR_SPECULAR, // Shader location: vector uniform: specular color - SHADER_LOC_COLOR_AMBIENT, // Shader location: vector uniform: ambient color - SHADER_LOC_MAP_ALBEDO, // Shader location: sampler2d texture: albedo (same as: SHADER_LOC_MAP_DIFFUSE) - SHADER_LOC_MAP_METALNESS, // Shader location: sampler2d texture: metalness (same as: SHADER_LOC_MAP_SPECULAR) - SHADER_LOC_MAP_NORMAL, // Shader location: sampler2d texture: normal - SHADER_LOC_MAP_ROUGHNESS, // Shader location: sampler2d texture: roughness - SHADER_LOC_MAP_OCCLUSION, // Shader location: sampler2d texture: occlusion - SHADER_LOC_MAP_EMISSION, // Shader location: sampler2d texture: emission - SHADER_LOC_MAP_HEIGHT, // Shader location: sampler2d texture: height - SHADER_LOC_MAP_CUBEMAP, // Shader location: samplerCube texture: cubemap - SHADER_LOC_MAP_IRRADIANCE, // Shader location: samplerCube texture: irradiance - SHADER_LOC_MAP_PREFILTER, // Shader location: samplerCube texture: prefilter - SHADER_LOC_MAP_BRDF, // Shader location: sampler2d texture: brdf - SHADER_LOC_VERTEX_BONEIDS, // Shader location: vertex attribute: boneIds - SHADER_LOC_VERTEX_BONEWEIGHTS, // Shader location: vertex attribute: boneWeights - SHADER_LOC_BONE_MATRICES // Shader location: array of matrices uniform: boneMatrices -} ShaderLocationIndex; - -#define SHADER_LOC_MAP_DIFFUSE SHADER_LOC_MAP_ALBEDO -#define SHADER_LOC_MAP_SPECULAR SHADER_LOC_MAP_METALNESS - -// Shader uniform data type -typedef enum { - SHADER_UNIFORM_FLOAT = 0, // Shader uniform type: float - SHADER_UNIFORM_VEC2, // Shader uniform type: vec2 (2 float) - SHADER_UNIFORM_VEC3, // Shader uniform type: vec3 (3 float) - SHADER_UNIFORM_VEC4, // Shader uniform type: vec4 (4 float) - SHADER_UNIFORM_INT, // Shader uniform type: int - SHADER_UNIFORM_IVEC2, // Shader uniform type: ivec2 (2 int) - SHADER_UNIFORM_IVEC3, // Shader uniform type: ivec3 (3 int) - SHADER_UNIFORM_IVEC4, // Shader uniform type: ivec4 (4 int) - SHADER_UNIFORM_SAMPLER2D // Shader uniform type: sampler2d -} ShaderUniformDataType; - -// Shader attribute data types -typedef enum { - SHADER_ATTRIB_FLOAT = 0, // Shader attribute type: float - SHADER_ATTRIB_VEC2, // Shader attribute type: vec2 (2 float) - SHADER_ATTRIB_VEC3, // Shader attribute type: vec3 (3 float) - SHADER_ATTRIB_VEC4 // Shader attribute type: vec4 (4 float) -} ShaderAttributeDataType; - -// Pixel formats -// NOTE: Support depends on OpenGL version and platform -typedef enum { - PIXELFORMAT_UNCOMPRESSED_GRAYSCALE = 1, // 8 bit per pixel (no alpha) - PIXELFORMAT_UNCOMPRESSED_GRAY_ALPHA, // 8*2 bpp (2 channels) - PIXELFORMAT_UNCOMPRESSED_R5G6B5, // 16 bpp - PIXELFORMAT_UNCOMPRESSED_R8G8B8, // 24 bpp - PIXELFORMAT_UNCOMPRESSED_R5G5B5A1, // 16 bpp (1 bit alpha) - PIXELFORMAT_UNCOMPRESSED_R4G4B4A4, // 16 bpp (4 bit alpha) - PIXELFORMAT_UNCOMPRESSED_R8G8B8A8, // 32 bpp - PIXELFORMAT_UNCOMPRESSED_R32, // 32 bpp (1 channel - float) - PIXELFORMAT_UNCOMPRESSED_R32G32B32, // 32*3 bpp (3 channels - float) - PIXELFORMAT_UNCOMPRESSED_R32G32B32A32, // 32*4 bpp (4 channels - float) - PIXELFORMAT_UNCOMPRESSED_R16, // 16 bpp (1 channel - half float) - PIXELFORMAT_UNCOMPRESSED_R16G16B16, // 16*3 bpp (3 channels - half float) - PIXELFORMAT_UNCOMPRESSED_R16G16B16A16, // 16*4 bpp (4 channels - half float) - PIXELFORMAT_COMPRESSED_DXT1_RGB, // 4 bpp (no alpha) - PIXELFORMAT_COMPRESSED_DXT1_RGBA, // 4 bpp (1 bit alpha) - PIXELFORMAT_COMPRESSED_DXT3_RGBA, // 8 bpp - PIXELFORMAT_COMPRESSED_DXT5_RGBA, // 8 bpp - PIXELFORMAT_COMPRESSED_ETC1_RGB, // 4 bpp - PIXELFORMAT_COMPRESSED_ETC2_RGB, // 4 bpp - PIXELFORMAT_COMPRESSED_ETC2_EAC_RGBA, // 8 bpp - PIXELFORMAT_COMPRESSED_PVRT_RGB, // 4 bpp - PIXELFORMAT_COMPRESSED_PVRT_RGBA, // 4 bpp - PIXELFORMAT_COMPRESSED_ASTC_4x4_RGBA, // 8 bpp - PIXELFORMAT_COMPRESSED_ASTC_8x8_RGBA // 2 bpp -} PixelFormat; - -// Texture parameters: filter mode -// NOTE 1: Filtering considers mipmaps if available in the texture -// NOTE 2: Filter is accordingly set for minification and magnification -typedef enum { - TEXTURE_FILTER_POINT = 0, // No filter, just pixel approximation - TEXTURE_FILTER_BILINEAR, // Linear filtering - TEXTURE_FILTER_TRILINEAR, // Trilinear filtering (linear with mipmaps) - TEXTURE_FILTER_ANISOTROPIC_4X, // Anisotropic filtering 4x - TEXTURE_FILTER_ANISOTROPIC_8X, // Anisotropic filtering 8x - TEXTURE_FILTER_ANISOTROPIC_16X, // Anisotropic filtering 16x -} TextureFilter; - -// Texture parameters: wrap mode -typedef enum { - TEXTURE_WRAP_REPEAT = 0, // Repeats texture in tiled mode - TEXTURE_WRAP_CLAMP, // Clamps texture to edge pixel in tiled mode - TEXTURE_WRAP_MIRROR_REPEAT, // Mirrors and repeats the texture in tiled mode - TEXTURE_WRAP_MIRROR_CLAMP // Mirrors and clamps to border the texture in tiled mode -} TextureWrap; - -// Cubemap layouts -typedef enum { - CUBEMAP_LAYOUT_AUTO_DETECT = 0, // Automatically detect layout type - CUBEMAP_LAYOUT_LINE_VERTICAL, // Layout is defined by a vertical line with faces - CUBEMAP_LAYOUT_LINE_HORIZONTAL, // Layout is defined by a horizontal line with faces - CUBEMAP_LAYOUT_CROSS_THREE_BY_FOUR, // Layout is defined by a 3x4 cross with cubemap faces - CUBEMAP_LAYOUT_CROSS_FOUR_BY_THREE // Layout is defined by a 4x3 cross with cubemap faces -} CubemapLayout; - -// Font type, defines generation method -typedef enum { - FONT_DEFAULT = 0, // Default font generation, anti-aliased - FONT_BITMAP, // Bitmap font generation, no anti-aliasing - FONT_SDF // SDF font generation, requires external shader -} FontType; - -// Color blending modes (pre-defined) -typedef enum { - BLEND_ALPHA = 0, // Blend textures considering alpha (default) - BLEND_ADDITIVE, // Blend textures adding colors - BLEND_MULTIPLIED, // Blend textures multiplying colors - BLEND_ADD_COLORS, // Blend textures adding colors (alternative) - BLEND_SUBTRACT_COLORS, // Blend textures subtracting colors (alternative) - BLEND_ALPHA_PREMULTIPLY, // Blend premultiplied textures considering alpha - BLEND_CUSTOM, // Blend textures using custom src/dst factors (use rlSetBlendFactors()) - BLEND_CUSTOM_SEPARATE // Blend textures using custom rgb/alpha separate src/dst factors (use rlSetBlendFactorsSeparate()) -} BlendMode; - -// Gesture -// NOTE: Provided as bit-wise flags to enable only desired gestures -typedef enum { - GESTURE_NONE = 0, // No gesture - GESTURE_TAP = 1, // Tap gesture - GESTURE_DOUBLETAP = 2, // Double tap gesture - GESTURE_HOLD = 4, // Hold gesture - GESTURE_DRAG = 8, // Drag gesture - GESTURE_SWIPE_RIGHT = 16, // Swipe right gesture - GESTURE_SWIPE_LEFT = 32, // Swipe left gesture - GESTURE_SWIPE_UP = 64, // Swipe up gesture - GESTURE_SWIPE_DOWN = 128, // Swipe down gesture - GESTURE_PINCH_IN = 256, // Pinch in gesture - GESTURE_PINCH_OUT = 512 // Pinch out gesture -} Gesture; - -// Camera system modes -typedef enum { - CAMERA_CUSTOM = 0, // Camera custom, controlled by user (UpdateCamera() does nothing) - CAMERA_FREE, // Camera free mode - CAMERA_ORBITAL, // Camera orbital, around target, zoom supported - CAMERA_FIRST_PERSON, // Camera first person - CAMERA_THIRD_PERSON // Camera third person -} CameraMode; - -// Camera projection -typedef enum { - CAMERA_PERSPECTIVE = 0, // Perspective projection - CAMERA_ORTHOGRAPHIC // Orthographic projection -} CameraProjection; - -// N-patch layout -typedef enum { - NPATCH_NINE_PATCH = 0, // Npatch layout: 3x3 tiles - NPATCH_THREE_PATCH_VERTICAL, // Npatch layout: 1x3 tiles - NPATCH_THREE_PATCH_HORIZONTAL // Npatch layout: 3x1 tiles -} NPatchLayout; - -// Callbacks to hook some internal functions -// WARNING: These callbacks are intended for advanced users -typedef void (*TraceLogCallback)(int logLevel, const char *text, va_list args); // Logging: Redirect trace log messages -typedef unsigned char *(*LoadFileDataCallback)(const char *fileName, int *dataSize); // FileIO: Load binary data -typedef bool (*SaveFileDataCallback)(const char *fileName, void *data, int dataSize); // FileIO: Save binary data -typedef char *(*LoadFileTextCallback)(const char *fileName); // FileIO: Load text data -typedef bool (*SaveFileTextCallback)(const char *fileName, char *text); // FileIO: Save text data - -//------------------------------------------------------------------------------------ -// Global Variables Definition -//------------------------------------------------------------------------------------ -// It's lonely here... - -//------------------------------------------------------------------------------------ -// Window and Graphics Device Functions (Module: core) -//------------------------------------------------------------------------------------ - -#if defined(__cplusplus) -extern "C" { // Prevents name mangling of functions -#endif - -// Window-related functions -RLAPI void InitWindow(int width, int height, const char *title); // Initialize window and OpenGL context -RLAPI void CloseWindow(void); // Close window and unload OpenGL context -RLAPI bool WindowShouldClose(void); // Check if application should close (KEY_ESCAPE pressed or windows close icon clicked) -RLAPI bool IsWindowReady(void); // Check if window has been initialized successfully -RLAPI bool IsWindowFullscreen(void); // Check if window is currently fullscreen -RLAPI bool IsWindowHidden(void); // Check if window is currently hidden -RLAPI bool IsWindowMinimized(void); // Check if window is currently minimized -RLAPI bool IsWindowMaximized(void); // Check if window is currently maximized -RLAPI bool IsWindowFocused(void); // Check if window is currently focused -RLAPI bool IsWindowResized(void); // Check if window has been resized last frame -RLAPI bool IsWindowState(unsigned int flag); // Check if one specific window flag is enabled -RLAPI void SetWindowState(unsigned int flags); // Set window configuration state using flags -RLAPI void ClearWindowState(unsigned int flags); // Clear window configuration state flags -RLAPI void ToggleFullscreen(void); // Toggle window state: fullscreen/windowed, resizes monitor to match window resolution -RLAPI void ToggleBorderlessWindowed(void); // Toggle window state: borderless windowed, resizes window to match monitor resolution -RLAPI void MaximizeWindow(void); // Set window state: maximized, if resizable -RLAPI void MinimizeWindow(void); // Set window state: minimized, if resizable -RLAPI void RestoreWindow(void); // Set window state: not minimized/maximized -RLAPI void SetWindowIcon(Image image); // Set icon for window (single image, RGBA 32bit) -RLAPI void SetWindowIcons(Image *images, int count); // Set icon for window (multiple images, RGBA 32bit) -RLAPI void SetWindowTitle(const char *title); // Set title for window -RLAPI void SetWindowPosition(int x, int y); // Set window position on screen -RLAPI void SetWindowMonitor(int monitor); // Set monitor for the current window -RLAPI void SetWindowMinSize(int width, int height); // Set window minimum dimensions (for FLAG_WINDOW_RESIZABLE) -RLAPI void SetWindowMaxSize(int width, int height); // Set window maximum dimensions (for FLAG_WINDOW_RESIZABLE) -RLAPI void SetWindowSize(int width, int height); // Set window dimensions -RLAPI void SetWindowOpacity(float opacity); // Set window opacity [0.0f..1.0f] -RLAPI void SetWindowFocused(void); // Set window focused -RLAPI void *GetWindowHandle(void); // Get native window handle -RLAPI int GetScreenWidth(void); // Get current screen width -RLAPI int GetScreenHeight(void); // Get current screen height -RLAPI int GetRenderWidth(void); // Get current render width (it considers HiDPI) -RLAPI int GetRenderHeight(void); // Get current render height (it considers HiDPI) -RLAPI int GetMonitorCount(void); // Get number of connected monitors -RLAPI int GetCurrentMonitor(void); // Get current monitor where window is placed -RLAPI Vector2 GetMonitorPosition(int monitor); // Get specified monitor position -RLAPI int GetMonitorWidth(int monitor); // Get specified monitor width (current video mode used by monitor) -RLAPI int GetMonitorHeight(int monitor); // Get specified monitor height (current video mode used by monitor) -RLAPI int GetMonitorPhysicalWidth(int monitor); // Get specified monitor physical width in millimetres -RLAPI int GetMonitorPhysicalHeight(int monitor); // Get specified monitor physical height in millimetres -RLAPI int GetMonitorRefreshRate(int monitor); // Get specified monitor refresh rate -RLAPI Vector2 GetWindowPosition(void); // Get window position XY on monitor -RLAPI Vector2 GetWindowScaleDPI(void); // Get window scale DPI factor -RLAPI const char *GetMonitorName(int monitor); // Get the human-readable, UTF-8 encoded name of the specified monitor -RLAPI void SetClipboardText(const char *text); // Set clipboard text content -RLAPI const char *GetClipboardText(void); // Get clipboard text content -RLAPI Image GetClipboardImage(void); // Get clipboard image content -RLAPI void EnableEventWaiting(void); // Enable waiting for events on EndDrawing(), no automatic event polling -RLAPI void DisableEventWaiting(void); // Disable waiting for events on EndDrawing(), automatic events polling - -// Cursor-related functions -RLAPI void ShowCursor(void); // Shows cursor -RLAPI void HideCursor(void); // Hides cursor -RLAPI bool IsCursorHidden(void); // Check if cursor is not visible -RLAPI void EnableCursor(void); // Enables cursor (unlock cursor) -RLAPI void DisableCursor(void); // Disables cursor (lock cursor) -RLAPI bool IsCursorOnScreen(void); // Check if cursor is on the screen - -// Drawing-related functions -RLAPI void ClearBackground(Color color); // Set background color (framebuffer clear color) -RLAPI void BeginDrawing(void); // Setup canvas (framebuffer) to start drawing -RLAPI void EndDrawing(void); // End canvas drawing and swap buffers (double buffering) -RLAPI void BeginMode2D(Camera2D camera); // Begin 2D mode with custom camera (2D) -RLAPI void EndMode2D(void); // Ends 2D mode with custom camera -RLAPI void BeginMode3D(Camera3D camera); // Begin 3D mode with custom camera (3D) -RLAPI void EndMode3D(void); // Ends 3D mode and returns to default 2D orthographic mode -RLAPI void BeginTextureMode(RenderTexture2D target); // Begin drawing to render texture -RLAPI void EndTextureMode(void); // Ends drawing to render texture -RLAPI void BeginShaderMode(Shader shader); // Begin custom shader drawing -RLAPI void EndShaderMode(void); // End custom shader drawing (use default shader) -RLAPI void BeginBlendMode(int mode); // Begin blending mode (alpha, additive, multiplied, subtract, custom) -RLAPI void EndBlendMode(void); // End blending mode (reset to default: alpha blending) -RLAPI void BeginScissorMode(int x, int y, int width, int height); // Begin scissor mode (define screen area for following drawing) -RLAPI void EndScissorMode(void); // End scissor mode -RLAPI void BeginVrStereoMode(VrStereoConfig config); // Begin stereo rendering (requires VR simulator) -RLAPI void EndVrStereoMode(void); // End stereo rendering (requires VR simulator) - -// VR stereo config functions for VR simulator -RLAPI VrStereoConfig LoadVrStereoConfig(VrDeviceInfo device); // Load VR stereo config for VR simulator device parameters -RLAPI void UnloadVrStereoConfig(VrStereoConfig config); // Unload VR stereo config - -// Shader management functions -// NOTE: Shader functionality is not available on OpenGL 1.1 -RLAPI Shader LoadShader(const char *vsFileName, const char *fsFileName); // Load shader from files and bind default locations -RLAPI Shader LoadShaderFromMemory(const char *vsCode, const char *fsCode); // Load shader from code strings and bind default locations -RLAPI bool IsShaderValid(Shader shader); // Check if a shader is valid (loaded on GPU) -RLAPI int GetShaderLocation(Shader shader, const char *uniformName); // Get shader uniform location -RLAPI int GetShaderLocationAttrib(Shader shader, const char *attribName); // Get shader attribute location -RLAPI void SetShaderValue(Shader shader, int locIndex, const void *value, int uniformType); // Set shader uniform value -RLAPI void SetShaderValueV(Shader shader, int locIndex, const void *value, int uniformType, int count); // Set shader uniform value vector -RLAPI void SetShaderValueMatrix(Shader shader, int locIndex, Matrix mat); // Set shader uniform value (matrix 4x4) -RLAPI void SetShaderValueTexture(Shader shader, int locIndex, Texture2D texture); // Set shader uniform value for texture (sampler2d) -RLAPI void UnloadShader(Shader shader); // Unload shader from GPU memory (VRAM) - -// Screen-space-related functions -#define GetMouseRay GetScreenToWorldRay // Compatibility hack for previous raylib versions -RLAPI Ray GetScreenToWorldRay(Vector2 position, Camera camera); // Get a ray trace from screen position (i.e mouse) -RLAPI Ray GetScreenToWorldRayEx(Vector2 position, Camera camera, int width, int height); // Get a ray trace from screen position (i.e mouse) in a viewport -RLAPI Vector2 GetWorldToScreen(Vector3 position, Camera camera); // Get the screen space position for a 3d world space position -RLAPI Vector2 GetWorldToScreenEx(Vector3 position, Camera camera, int width, int height); // Get size position for a 3d world space position -RLAPI Vector2 GetWorldToScreen2D(Vector2 position, Camera2D camera); // Get the screen space position for a 2d camera world space position -RLAPI Vector2 GetScreenToWorld2D(Vector2 position, Camera2D camera); // Get the world space position for a 2d camera screen space position -RLAPI Matrix GetCameraMatrix(Camera camera); // Get camera transform matrix (view matrix) -RLAPI Matrix GetCameraMatrix2D(Camera2D camera); // Get camera 2d transform matrix - -// Timing-related functions -RLAPI void SetTargetFPS(int fps); // Set target FPS (maximum) -RLAPI float GetFrameTime(void); // Get time in seconds for last frame drawn (delta time) -RLAPI double GetTime(void); // Get elapsed time in seconds since InitWindow() -RLAPI int GetFPS(void); // Get current FPS - -// Custom frame control functions -// NOTE: Those functions are intended for advanced users that want full control over the frame processing -// By default EndDrawing() does this job: draws everything + SwapScreenBuffer() + manage frame timing + PollInputEvents() -// To avoid that behaviour and control frame processes manually, enable in config.h: SUPPORT_CUSTOM_FRAME_CONTROL -RLAPI void SwapScreenBuffer(void); // Swap back buffer with front buffer (screen drawing) -RLAPI void PollInputEvents(void); // Register all input events -RLAPI void WaitTime(double seconds); // Wait for some time (halt program execution) - -// Random values generation functions -RLAPI void SetRandomSeed(unsigned int seed); // Set the seed for the random number generator -RLAPI int GetRandomValue(int min, int max); // Get a random value between min and max (both included) -RLAPI int *LoadRandomSequence(unsigned int count, int min, int max); // Load random values sequence, no values repeated -RLAPI void UnloadRandomSequence(int *sequence); // Unload random values sequence - -// Misc. functions -RLAPI void TakeScreenshot(const char *fileName); // Takes a screenshot of current screen (filename extension defines format) -RLAPI void SetConfigFlags(unsigned int flags); // Setup init configuration flags (view FLAGS) -RLAPI void OpenURL(const char *url); // Open URL with default system browser (if available) - -// NOTE: Following functions implemented in module [utils] -//------------------------------------------------------------------ -RLAPI void TraceLog(int logLevel, const char *text, ...); // Show trace log messages (LOG_DEBUG, LOG_INFO, LOG_WARNING, LOG_ERROR...) -RLAPI void SetTraceLogLevel(int logLevel); // Set the current threshold (minimum) log level -RLAPI void *MemAlloc(unsigned int size); // Internal memory allocator -RLAPI void *MemRealloc(void *ptr, unsigned int size); // Internal memory reallocator -RLAPI void MemFree(void *ptr); // Internal memory free - -// Set custom callbacks -// WARNING: Callbacks setup is intended for advanced users -RLAPI void SetTraceLogCallback(TraceLogCallback callback); // Set custom trace log -RLAPI void SetLoadFileDataCallback(LoadFileDataCallback callback); // Set custom file binary data loader -RLAPI void SetSaveFileDataCallback(SaveFileDataCallback callback); // Set custom file binary data saver -RLAPI void SetLoadFileTextCallback(LoadFileTextCallback callback); // Set custom file text data loader -RLAPI void SetSaveFileTextCallback(SaveFileTextCallback callback); // Set custom file text data saver - -// Files management functions -RLAPI unsigned char *LoadFileData(const char *fileName, int *dataSize); // Load file data as byte array (read) -RLAPI void UnloadFileData(unsigned char *data); // Unload file data allocated by LoadFileData() -RLAPI bool SaveFileData(const char *fileName, void *data, int dataSize); // Save data to file from byte array (write), returns true on success -RLAPI bool ExportDataAsCode(const unsigned char *data, int dataSize, const char *fileName); // Export data to code (.h), returns true on success -RLAPI char *LoadFileText(const char *fileName); // Load text data from file (read), returns a '\0' terminated string -RLAPI void UnloadFileText(char *text); // Unload file text data allocated by LoadFileText() -RLAPI bool SaveFileText(const char *fileName, char *text); // Save text data to file (write), string must be '\0' terminated, returns true on success -//------------------------------------------------------------------ - -// File system functions -RLAPI bool FileExists(const char *fileName); // Check if file exists -RLAPI bool DirectoryExists(const char *dirPath); // Check if a directory path exists -RLAPI bool IsFileExtension(const char *fileName, const char *ext); // Check file extension (including point: .png, .wav) -RLAPI int GetFileLength(const char *fileName); // Get file length in bytes (NOTE: GetFileSize() conflicts with windows.h) -RLAPI const char *GetFileExtension(const char *fileName); // Get pointer to extension for a filename string (includes dot: '.png') -RLAPI const char *GetFileName(const char *filePath); // Get pointer to filename for a path string -RLAPI const char *GetFileNameWithoutExt(const char *filePath); // Get filename string without extension (uses static string) -RLAPI const char *GetDirectoryPath(const char *filePath); // Get full path for a given fileName with path (uses static string) -RLAPI const char *GetPrevDirectoryPath(const char *dirPath); // Get previous directory path for a given path (uses static string) -RLAPI const char *GetWorkingDirectory(void); // Get current working directory (uses static string) -RLAPI const char *GetApplicationDirectory(void); // Get the directory of the running application (uses static string) -RLAPI int MakeDirectory(const char *dirPath); // Create directories (including full path requested), returns 0 on success -RLAPI bool ChangeDirectory(const char *dir); // Change working directory, return true on success -RLAPI bool IsPathFile(const char *path); // Check if a given path is a file or a directory -RLAPI bool IsFileNameValid(const char *fileName); // Check if fileName is valid for the platform/OS -RLAPI FilePathList LoadDirectoryFiles(const char *dirPath); // Load directory filepaths -RLAPI FilePathList LoadDirectoryFilesEx(const char *basePath, const char *filter, bool scanSubdirs); // Load directory filepaths with extension filtering and recursive directory scan. Use 'DIR' in the filter string to include directories in the result -RLAPI void UnloadDirectoryFiles(FilePathList files); // Unload filepaths -RLAPI bool IsFileDropped(void); // Check if a file has been dropped into window -RLAPI FilePathList LoadDroppedFiles(void); // Load dropped filepaths -RLAPI void UnloadDroppedFiles(FilePathList files); // Unload dropped filepaths -RLAPI long GetFileModTime(const char *fileName); // Get file modification time (last write time) - -// Compression/Encoding functionality -RLAPI unsigned char *CompressData(const unsigned char *data, int dataSize, int *compDataSize); // Compress data (DEFLATE algorithm), memory must be MemFree() -RLAPI unsigned char *DecompressData(const unsigned char *compData, int compDataSize, int *dataSize); // Decompress data (DEFLATE algorithm), memory must be MemFree() -RLAPI char *EncodeDataBase64(const unsigned char *data, int dataSize, int *outputSize); // Encode data to Base64 string, memory must be MemFree() -RLAPI unsigned char *DecodeDataBase64(const unsigned char *data, int *outputSize); // Decode Base64 string data, memory must be MemFree() -RLAPI unsigned int ComputeCRC32(unsigned char *data, int dataSize); // Compute CRC32 hash code -RLAPI unsigned int *ComputeMD5(unsigned char *data, int dataSize); // Compute MD5 hash code, returns static int[4] (16 bytes) -RLAPI unsigned int *ComputeSHA1(unsigned char *data, int dataSize); // Compute SHA1 hash code, returns static int[5] (20 bytes) - - -// Automation events functionality -RLAPI AutomationEventList LoadAutomationEventList(const char *fileName); // Load automation events list from file, NULL for empty list, capacity = MAX_AUTOMATION_EVENTS -RLAPI void UnloadAutomationEventList(AutomationEventList list); // Unload automation events list from file -RLAPI bool ExportAutomationEventList(AutomationEventList list, const char *fileName); // Export automation events list as text file -RLAPI void SetAutomationEventList(AutomationEventList *list); // Set automation event list to record to -RLAPI void SetAutomationEventBaseFrame(int frame); // Set automation event internal base frame to start recording -RLAPI void StartAutomationEventRecording(void); // Start recording automation events (AutomationEventList must be set) -RLAPI void StopAutomationEventRecording(void); // Stop recording automation events -RLAPI void PlayAutomationEvent(AutomationEvent event); // Play a recorded automation event - -//------------------------------------------------------------------------------------ -// Input Handling Functions (Module: core) -//------------------------------------------------------------------------------------ - -// Input-related functions: keyboard -RLAPI bool IsKeyPressed(int key); // Check if a key has been pressed once -RLAPI bool IsKeyPressedRepeat(int key); // Check if a key has been pressed again -RLAPI bool IsKeyDown(int key); // Check if a key is being pressed -RLAPI bool IsKeyReleased(int key); // Check if a key has been released once -RLAPI bool IsKeyUp(int key); // Check if a key is NOT being pressed -RLAPI int GetKeyPressed(void); // Get key pressed (keycode), call it multiple times for keys queued, returns 0 when the queue is empty -RLAPI int GetCharPressed(void); // Get char pressed (unicode), call it multiple times for chars queued, returns 0 when the queue is empty -RLAPI void SetExitKey(int key); // Set a custom key to exit program (default is ESC) - -// Input-related functions: gamepads -RLAPI bool IsGamepadAvailable(int gamepad); // Check if a gamepad is available -RLAPI const char *GetGamepadName(int gamepad); // Get gamepad internal name id -RLAPI bool IsGamepadButtonPressed(int gamepad, int button); // Check if a gamepad button has been pressed once -RLAPI bool IsGamepadButtonDown(int gamepad, int button); // Check if a gamepad button is being pressed -RLAPI bool IsGamepadButtonReleased(int gamepad, int button); // Check if a gamepad button has been released once -RLAPI bool IsGamepadButtonUp(int gamepad, int button); // Check if a gamepad button is NOT being pressed -RLAPI int GetGamepadButtonPressed(void); // Get the last gamepad button pressed -RLAPI int GetGamepadAxisCount(int gamepad); // Get gamepad axis count for a gamepad -RLAPI float GetGamepadAxisMovement(int gamepad, int axis); // Get axis movement value for a gamepad axis -RLAPI int SetGamepadMappings(const char *mappings); // Set internal gamepad mappings (SDL_GameControllerDB) -RLAPI void SetGamepadVibration(int gamepad, float leftMotor, float rightMotor, float duration); // Set gamepad vibration for both motors (duration in seconds) - -// Input-related functions: mouse -RLAPI bool IsMouseButtonPressed(int button); // Check if a mouse button has been pressed once -RLAPI bool IsMouseButtonDown(int button); // Check if a mouse button is being pressed -RLAPI bool IsMouseButtonReleased(int button); // Check if a mouse button has been released once -RLAPI bool IsMouseButtonUp(int button); // Check if a mouse button is NOT being pressed -RLAPI int GetMouseX(void); // Get mouse position X -RLAPI int GetMouseY(void); // Get mouse position Y -RLAPI Vector2 GetMousePosition(void); // Get mouse position XY -RLAPI Vector2 GetMouseDelta(void); // Get mouse delta between frames -RLAPI void SetMousePosition(int x, int y); // Set mouse position XY -RLAPI void SetMouseOffset(int offsetX, int offsetY); // Set mouse offset -RLAPI void SetMouseScale(float scaleX, float scaleY); // Set mouse scaling -RLAPI float GetMouseWheelMove(void); // Get mouse wheel movement for X or Y, whichever is larger -RLAPI Vector2 GetMouseWheelMoveV(void); // Get mouse wheel movement for both X and Y -RLAPI void SetMouseCursor(int cursor); // Set mouse cursor - -// Input-related functions: touch -RLAPI int GetTouchX(void); // Get touch position X for touch point 0 (relative to screen size) -RLAPI int GetTouchY(void); // Get touch position Y for touch point 0 (relative to screen size) -RLAPI Vector2 GetTouchPosition(int index); // Get touch position XY for a touch point index (relative to screen size) -RLAPI int GetTouchPointId(int index); // Get touch point identifier for given index -RLAPI int GetTouchPointCount(void); // Get number of touch points - -//------------------------------------------------------------------------------------ -// Gestures and Touch Handling Functions (Module: rgestures) -//------------------------------------------------------------------------------------ -RLAPI void SetGesturesEnabled(unsigned int flags); // Enable a set of gestures using flags -RLAPI bool IsGestureDetected(unsigned int gesture); // Check if a gesture have been detected -RLAPI int GetGestureDetected(void); // Get latest detected gesture -RLAPI float GetGestureHoldDuration(void); // Get gesture hold time in seconds -RLAPI Vector2 GetGestureDragVector(void); // Get gesture drag vector -RLAPI float GetGestureDragAngle(void); // Get gesture drag angle -RLAPI Vector2 GetGesturePinchVector(void); // Get gesture pinch delta -RLAPI float GetGesturePinchAngle(void); // Get gesture pinch angle - -//------------------------------------------------------------------------------------ -// Camera System Functions (Module: rcamera) -//------------------------------------------------------------------------------------ -RLAPI void UpdateCamera(Camera *camera, int mode); // Update camera position for selected mode -RLAPI void UpdateCameraPro(Camera *camera, Vector3 movement, Vector3 rotation, float zoom); // Update camera movement/rotation - -//------------------------------------------------------------------------------------ -// Basic Shapes Drawing Functions (Module: shapes) -//------------------------------------------------------------------------------------ -// Set texture and rectangle to be used on shapes drawing -// NOTE: It can be useful when using basic shapes and one single font, -// defining a font char white rectangle would allow drawing everything in a single draw call -RLAPI void SetShapesTexture(Texture2D texture, Rectangle source); // Set texture and rectangle to be used on shapes drawing -RLAPI Texture2D GetShapesTexture(void); // Get texture that is used for shapes drawing -RLAPI Rectangle GetShapesTextureRectangle(void); // Get texture source rectangle that is used for shapes drawing - -// Basic shapes drawing functions -RLAPI void DrawPixel(int posX, int posY, Color color); // Draw a pixel using geometry [Can be slow, use with care] -RLAPI void DrawPixelV(Vector2 position, Color color); // Draw a pixel using geometry (Vector version) [Can be slow, use with care] -RLAPI void DrawLine(int startPosX, int startPosY, int endPosX, int endPosY, Color color); // Draw a line -RLAPI void DrawLineV(Vector2 startPos, Vector2 endPos, Color color); // Draw a line (using gl lines) -RLAPI void DrawLineEx(Vector2 startPos, Vector2 endPos, float thick, Color color); // Draw a line (using triangles/quads) -RLAPI void DrawLineStrip(const Vector2 *points, int pointCount, Color color); // Draw lines sequence (using gl lines) -RLAPI void DrawLineBezier(Vector2 startPos, Vector2 endPos, float thick, Color color); // Draw line segment cubic-bezier in-out interpolation -RLAPI void DrawCircle(int centerX, int centerY, float radius, Color color); // Draw a color-filled circle -RLAPI void DrawCircleSector(Vector2 center, float radius, float startAngle, float endAngle, int segments, Color color); // Draw a piece of a circle -RLAPI void DrawCircleSectorLines(Vector2 center, float radius, float startAngle, float endAngle, int segments, Color color); // Draw circle sector outline -RLAPI void DrawCircleGradient(int centerX, int centerY, float radius, Color inner, Color outer); // Draw a gradient-filled circle -RLAPI void DrawCircleV(Vector2 center, float radius, Color color); // Draw a color-filled circle (Vector version) -RLAPI void DrawCircleLines(int centerX, int centerY, float radius, Color color); // Draw circle outline -RLAPI void DrawCircleLinesV(Vector2 center, float radius, Color color); // Draw circle outline (Vector version) -RLAPI void DrawEllipse(int centerX, int centerY, float radiusH, float radiusV, Color color); // Draw ellipse -RLAPI void DrawEllipseLines(int centerX, int centerY, float radiusH, float radiusV, Color color); // Draw ellipse outline -RLAPI void DrawRing(Vector2 center, float innerRadius, float outerRadius, float startAngle, float endAngle, int segments, Color color); // Draw ring -RLAPI void DrawRingLines(Vector2 center, float innerRadius, float outerRadius, float startAngle, float endAngle, int segments, Color color); // Draw ring outline -RLAPI void DrawRectangle(int posX, int posY, int width, int height, Color color); // Draw a color-filled rectangle -RLAPI void DrawRectangleV(Vector2 position, Vector2 size, Color color); // Draw a color-filled rectangle (Vector version) -RLAPI void DrawRectangleRec(Rectangle rec, Color color); // Draw a color-filled rectangle -RLAPI void DrawRectanglePro(Rectangle rec, Vector2 origin, float rotation, Color color); // Draw a color-filled rectangle with pro parameters -RLAPI void DrawRectangleGradientV(int posX, int posY, int width, int height, Color top, Color bottom); // Draw a vertical-gradient-filled rectangle -RLAPI void DrawRectangleGradientH(int posX, int posY, int width, int height, Color left, Color right); // Draw a horizontal-gradient-filled rectangle -RLAPI void DrawRectangleGradientEx(Rectangle rec, Color topLeft, Color bottomLeft, Color topRight, Color bottomRight); // Draw a gradient-filled rectangle with custom vertex colors -RLAPI void DrawRectangleLines(int posX, int posY, int width, int height, Color color); // Draw rectangle outline -RLAPI void DrawRectangleLinesEx(Rectangle rec, float lineThick, Color color); // Draw rectangle outline with extended parameters -RLAPI void DrawRectangleRounded(Rectangle rec, float roundness, int segments, Color color); // Draw rectangle with rounded edges -RLAPI void DrawRectangleRoundedLines(Rectangle rec, float roundness, int segments, Color color); // Draw rectangle lines with rounded edges -RLAPI void DrawRectangleRoundedLinesEx(Rectangle rec, float roundness, int segments, float lineThick, Color color); // Draw rectangle with rounded edges outline -RLAPI void DrawTriangle(Vector2 v1, Vector2 v2, Vector2 v3, Color color); // Draw a color-filled triangle (vertex in counter-clockwise order!) -RLAPI void DrawTriangleLines(Vector2 v1, Vector2 v2, Vector2 v3, Color color); // Draw triangle outline (vertex in counter-clockwise order!) -RLAPI void DrawTriangleFan(const Vector2 *points, int pointCount, Color color); // Draw a triangle fan defined by points (first vertex is the center) -RLAPI void DrawTriangleStrip(const Vector2 *points, int pointCount, Color color); // Draw a triangle strip defined by points -RLAPI void DrawPoly(Vector2 center, int sides, float radius, float rotation, Color color); // Draw a regular polygon (Vector version) -RLAPI void DrawPolyLines(Vector2 center, int sides, float radius, float rotation, Color color); // Draw a polygon outline of n sides -RLAPI void DrawPolyLinesEx(Vector2 center, int sides, float radius, float rotation, float lineThick, Color color); // Draw a polygon outline of n sides with extended parameters - -// Splines drawing functions -RLAPI void DrawSplineLinear(const Vector2 *points, int pointCount, float thick, Color color); // Draw spline: Linear, minimum 2 points -RLAPI void DrawSplineBasis(const Vector2 *points, int pointCount, float thick, Color color); // Draw spline: B-Spline, minimum 4 points -RLAPI void DrawSplineCatmullRom(const Vector2 *points, int pointCount, float thick, Color color); // Draw spline: Catmull-Rom, minimum 4 points -RLAPI void DrawSplineBezierQuadratic(const Vector2 *points, int pointCount, float thick, Color color); // Draw spline: Quadratic Bezier, minimum 3 points (1 control point): [p1, c2, p3, c4...] -RLAPI void DrawSplineBezierCubic(const Vector2 *points, int pointCount, float thick, Color color); // Draw spline: Cubic Bezier, minimum 4 points (2 control points): [p1, c2, c3, p4, c5, c6...] -RLAPI void DrawSplineSegmentLinear(Vector2 p1, Vector2 p2, float thick, Color color); // Draw spline segment: Linear, 2 points -RLAPI void DrawSplineSegmentBasis(Vector2 p1, Vector2 p2, Vector2 p3, Vector2 p4, float thick, Color color); // Draw spline segment: B-Spline, 4 points -RLAPI void DrawSplineSegmentCatmullRom(Vector2 p1, Vector2 p2, Vector2 p3, Vector2 p4, float thick, Color color); // Draw spline segment: Catmull-Rom, 4 points -RLAPI void DrawSplineSegmentBezierQuadratic(Vector2 p1, Vector2 c2, Vector2 p3, float thick, Color color); // Draw spline segment: Quadratic Bezier, 2 points, 1 control point -RLAPI void DrawSplineSegmentBezierCubic(Vector2 p1, Vector2 c2, Vector2 c3, Vector2 p4, float thick, Color color); // Draw spline segment: Cubic Bezier, 2 points, 2 control points - -// Spline segment point evaluation functions, for a given t [0.0f .. 1.0f] -RLAPI Vector2 GetSplinePointLinear(Vector2 startPos, Vector2 endPos, float t); // Get (evaluate) spline point: Linear -RLAPI Vector2 GetSplinePointBasis(Vector2 p1, Vector2 p2, Vector2 p3, Vector2 p4, float t); // Get (evaluate) spline point: B-Spline -RLAPI Vector2 GetSplinePointCatmullRom(Vector2 p1, Vector2 p2, Vector2 p3, Vector2 p4, float t); // Get (evaluate) spline point: Catmull-Rom -RLAPI Vector2 GetSplinePointBezierQuad(Vector2 p1, Vector2 c2, Vector2 p3, float t); // Get (evaluate) spline point: Quadratic Bezier -RLAPI Vector2 GetSplinePointBezierCubic(Vector2 p1, Vector2 c2, Vector2 c3, Vector2 p4, float t); // Get (evaluate) spline point: Cubic Bezier - -// Basic shapes collision detection functions -RLAPI bool CheckCollisionRecs(Rectangle rec1, Rectangle rec2); // Check collision between two rectangles -RLAPI bool CheckCollisionCircles(Vector2 center1, float radius1, Vector2 center2, float radius2); // Check collision between two circles -RLAPI bool CheckCollisionCircleRec(Vector2 center, float radius, Rectangle rec); // Check collision between circle and rectangle -RLAPI bool CheckCollisionCircleLine(Vector2 center, float radius, Vector2 p1, Vector2 p2); // Check if circle collides with a line created betweeen two points [p1] and [p2] -RLAPI bool CheckCollisionPointRec(Vector2 point, Rectangle rec); // Check if point is inside rectangle -RLAPI bool CheckCollisionPointCircle(Vector2 point, Vector2 center, float radius); // Check if point is inside circle -RLAPI bool CheckCollisionPointTriangle(Vector2 point, Vector2 p1, Vector2 p2, Vector2 p3); // Check if point is inside a triangle -RLAPI bool CheckCollisionPointLine(Vector2 point, Vector2 p1, Vector2 p2, int threshold); // Check if point belongs to line created between two points [p1] and [p2] with defined margin in pixels [threshold] -RLAPI bool CheckCollisionPointPoly(Vector2 point, const Vector2 *points, int pointCount); // Check if point is within a polygon described by array of vertices -RLAPI bool CheckCollisionLines(Vector2 startPos1, Vector2 endPos1, Vector2 startPos2, Vector2 endPos2, Vector2 *collisionPoint); // Check the collision between two lines defined by two points each, returns collision point by reference -RLAPI Rectangle GetCollisionRec(Rectangle rec1, Rectangle rec2); // Get collision rectangle for two rectangles collision - -//------------------------------------------------------------------------------------ -// Texture Loading and Drawing Functions (Module: textures) -//------------------------------------------------------------------------------------ - -// Image loading functions -// NOTE: These functions do not require GPU access -RLAPI Image LoadImage(const char *fileName); // Load image from file into CPU memory (RAM) -RLAPI Image LoadImageRaw(const char *fileName, int width, int height, int format, int headerSize); // Load image from RAW file data -RLAPI Image LoadImageAnim(const char *fileName, int *frames); // Load image sequence from file (frames appended to image.data) -RLAPI Image LoadImageAnimFromMemory(const char *fileType, const unsigned char *fileData, int dataSize, int *frames); // Load image sequence from memory buffer -RLAPI Image LoadImageFromMemory(const char *fileType, const unsigned char *fileData, int dataSize); // Load image from memory buffer, fileType refers to extension: i.e. '.png' -RLAPI Image LoadImageFromTexture(Texture2D texture); // Load image from GPU texture data -RLAPI Image LoadImageFromScreen(void); // Load image from screen buffer and (screenshot) -RLAPI bool IsImageValid(Image image); // Check if an image is valid (data and parameters) -RLAPI void UnloadImage(Image image); // Unload image from CPU memory (RAM) -RLAPI bool ExportImage(Image image, const char *fileName); // Export image data to file, returns true on success -RLAPI unsigned char *ExportImageToMemory(Image image, const char *fileType, int *fileSize); // Export image to memory buffer -RLAPI bool ExportImageAsCode(Image image, const char *fileName); // Export image as code file defining an array of bytes, returns true on success - -// Image generation functions -RLAPI Image GenImageColor(int width, int height, Color color); // Generate image: plain color -RLAPI Image GenImageGradientLinear(int width, int height, int direction, Color start, Color end); // Generate image: linear gradient, direction in degrees [0..360], 0=Vertical gradient -RLAPI Image GenImageGradientRadial(int width, int height, float density, Color inner, Color outer); // Generate image: radial gradient -RLAPI Image GenImageGradientSquare(int width, int height, float density, Color inner, Color outer); // Generate image: square gradient -RLAPI Image GenImageChecked(int width, int height, int checksX, int checksY, Color col1, Color col2); // Generate image: checked -RLAPI Image GenImageWhiteNoise(int width, int height, float factor); // Generate image: white noise -RLAPI Image GenImagePerlinNoise(int width, int height, int offsetX, int offsetY, float scale); // Generate image: perlin noise -RLAPI Image GenImageCellular(int width, int height, int tileSize); // Generate image: cellular algorithm, bigger tileSize means bigger cells -RLAPI Image GenImageText(int width, int height, const char *text); // Generate image: grayscale image from text data - -// Image manipulation functions -RLAPI Image ImageCopy(Image image); // Create an image duplicate (useful for transformations) -RLAPI Image ImageFromImage(Image image, Rectangle rec); // Create an image from another image piece -RLAPI Image ImageFromChannel(Image image, int selectedChannel); // Create an image from a selected channel of another image (GRAYSCALE) -RLAPI Image ImageText(const char *text, int fontSize, Color color); // Create an image from text (default font) -RLAPI Image ImageTextEx(Font font, const char *text, float fontSize, float spacing, Color tint); // Create an image from text (custom sprite font) -RLAPI void ImageFormat(Image *image, int newFormat); // Convert image data to desired format -RLAPI void ImageToPOT(Image *image, Color fill); // Convert image to POT (power-of-two) -RLAPI void ImageCrop(Image *image, Rectangle crop); // Crop an image to a defined rectangle -RLAPI void ImageAlphaCrop(Image *image, float threshold); // Crop image depending on alpha value -RLAPI void ImageAlphaClear(Image *image, Color color, float threshold); // Clear alpha channel to desired color -RLAPI void ImageAlphaMask(Image *image, Image alphaMask); // Apply alpha mask to image -RLAPI void ImageAlphaPremultiply(Image *image); // Premultiply alpha channel -RLAPI void ImageBlurGaussian(Image *image, int blurSize); // Apply Gaussian blur using a box blur approximation -RLAPI void ImageKernelConvolution(Image *image, const float *kernel, int kernelSize); // Apply custom square convolution kernel to image -RLAPI void ImageResize(Image *image, int newWidth, int newHeight); // Resize image (Bicubic scaling algorithm) -RLAPI void ImageResizeNN(Image *image, int newWidth,int newHeight); // Resize image (Nearest-Neighbor scaling algorithm) -RLAPI void ImageResizeCanvas(Image *image, int newWidth, int newHeight, int offsetX, int offsetY, Color fill); // Resize canvas and fill with color -RLAPI void ImageMipmaps(Image *image); // Compute all mipmap levels for a provided image -RLAPI void ImageDither(Image *image, int rBpp, int gBpp, int bBpp, int aBpp); // Dither image data to 16bpp or lower (Floyd-Steinberg dithering) -RLAPI void ImageFlipVertical(Image *image); // Flip image vertically -RLAPI void ImageFlipHorizontal(Image *image); // Flip image horizontally -RLAPI void ImageRotate(Image *image, int degrees); // Rotate image by input angle in degrees (-359 to 359) -RLAPI void ImageRotateCW(Image *image); // Rotate image clockwise 90deg -RLAPI void ImageRotateCCW(Image *image); // Rotate image counter-clockwise 90deg -RLAPI void ImageColorTint(Image *image, Color color); // Modify image color: tint -RLAPI void ImageColorInvert(Image *image); // Modify image color: invert -RLAPI void ImageColorGrayscale(Image *image); // Modify image color: grayscale -RLAPI void ImageColorContrast(Image *image, float contrast); // Modify image color: contrast (-100 to 100) -RLAPI void ImageColorBrightness(Image *image, int brightness); // Modify image color: brightness (-255 to 255) -RLAPI void ImageColorReplace(Image *image, Color color, Color replace); // Modify image color: replace color -RLAPI Color *LoadImageColors(Image image); // Load color data from image as a Color array (RGBA - 32bit) -RLAPI Color *LoadImagePalette(Image image, int maxPaletteSize, int *colorCount); // Load colors palette from image as a Color array (RGBA - 32bit) -RLAPI void UnloadImageColors(Color *colors); // Unload color data loaded with LoadImageColors() -RLAPI void UnloadImagePalette(Color *colors); // Unload colors palette loaded with LoadImagePalette() -RLAPI Rectangle GetImageAlphaBorder(Image image, float threshold); // Get image alpha border rectangle -RLAPI Color GetImageColor(Image image, int x, int y); // Get image pixel color at (x, y) position - -// Image drawing functions -// NOTE: Image software-rendering functions (CPU) -RLAPI void ImageClearBackground(Image *dst, Color color); // Clear image background with given color -RLAPI void ImageDrawPixel(Image *dst, int posX, int posY, Color color); // Draw pixel within an image -RLAPI void ImageDrawPixelV(Image *dst, Vector2 position, Color color); // Draw pixel within an image (Vector version) -RLAPI void ImageDrawLine(Image *dst, int startPosX, int startPosY, int endPosX, int endPosY, Color color); // Draw line within an image -RLAPI void ImageDrawLineV(Image *dst, Vector2 start, Vector2 end, Color color); // Draw line within an image (Vector version) -RLAPI void ImageDrawLineEx(Image *dst, Vector2 start, Vector2 end, int thick, Color color); // Draw a line defining thickness within an image -RLAPI void ImageDrawCircle(Image *dst, int centerX, int centerY, int radius, Color color); // Draw a filled circle within an image -RLAPI void ImageDrawCircleV(Image *dst, Vector2 center, int radius, Color color); // Draw a filled circle within an image (Vector version) -RLAPI void ImageDrawCircleLines(Image *dst, int centerX, int centerY, int radius, Color color); // Draw circle outline within an image -RLAPI void ImageDrawCircleLinesV(Image *dst, Vector2 center, int radius, Color color); // Draw circle outline within an image (Vector version) -RLAPI void ImageDrawRectangle(Image *dst, int posX, int posY, int width, int height, Color color); // Draw rectangle within an image -RLAPI void ImageDrawRectangleV(Image *dst, Vector2 position, Vector2 size, Color color); // Draw rectangle within an image (Vector version) -RLAPI void ImageDrawRectangleRec(Image *dst, Rectangle rec, Color color); // Draw rectangle within an image -RLAPI void ImageDrawRectangleLines(Image *dst, Rectangle rec, int thick, Color color); // Draw rectangle lines within an image -RLAPI void ImageDrawTriangle(Image *dst, Vector2 v1, Vector2 v2, Vector2 v3, Color color); // Draw triangle within an image -RLAPI void ImageDrawTriangleEx(Image *dst, Vector2 v1, Vector2 v2, Vector2 v3, Color c1, Color c2, Color c3); // Draw triangle with interpolated colors within an image -RLAPI void ImageDrawTriangleLines(Image *dst, Vector2 v1, Vector2 v2, Vector2 v3, Color color); // Draw triangle outline within an image -RLAPI void ImageDrawTriangleFan(Image *dst, Vector2 *points, int pointCount, Color color); // Draw a triangle fan defined by points within an image (first vertex is the center) -RLAPI void ImageDrawTriangleStrip(Image *dst, Vector2 *points, int pointCount, Color color); // Draw a triangle strip defined by points within an image -RLAPI void ImageDraw(Image *dst, Image src, Rectangle srcRec, Rectangle dstRec, Color tint); // Draw a source image within a destination image (tint applied to source) -RLAPI void ImageDrawText(Image *dst, const char *text, int posX, int posY, int fontSize, Color color); // Draw text (using default font) within an image (destination) -RLAPI void ImageDrawTextEx(Image *dst, Font font, const char *text, Vector2 position, float fontSize, float spacing, Color tint); // Draw text (custom sprite font) within an image (destination) - -// Texture loading functions -// NOTE: These functions require GPU access -RLAPI Texture2D LoadTexture(const char *fileName); // Load texture from file into GPU memory (VRAM) -RLAPI Texture2D LoadTextureFromImage(Image image); // Load texture from image data -RLAPI TextureCubemap LoadTextureCubemap(Image image, int layout); // Load cubemap from image, multiple image cubemap layouts supported -RLAPI RenderTexture2D LoadRenderTexture(int width, int height); // Load texture for rendering (framebuffer) -RLAPI bool IsTextureValid(Texture2D texture); // Check if a texture is valid (loaded in GPU) -RLAPI void UnloadTexture(Texture2D texture); // Unload texture from GPU memory (VRAM) -RLAPI bool IsRenderTextureValid(RenderTexture2D target); // Check if a render texture is valid (loaded in GPU) -RLAPI void UnloadRenderTexture(RenderTexture2D target); // Unload render texture from GPU memory (VRAM) -RLAPI void UpdateTexture(Texture2D texture, const void *pixels); // Update GPU texture with new data -RLAPI void UpdateTextureRec(Texture2D texture, Rectangle rec, const void *pixels); // Update GPU texture rectangle with new data - -// Texture configuration functions -RLAPI void GenTextureMipmaps(Texture2D *texture); // Generate GPU mipmaps for a texture -RLAPI void SetTextureFilter(Texture2D texture, int filter); // Set texture scaling filter mode -RLAPI void SetTextureWrap(Texture2D texture, int wrap); // Set texture wrapping mode - -// Texture drawing functions -RLAPI void DrawTexture(Texture2D texture, int posX, int posY, Color tint); // Draw a Texture2D -RLAPI void DrawTextureV(Texture2D texture, Vector2 position, Color tint); // Draw a Texture2D with position defined as Vector2 -RLAPI void DrawTextureEx(Texture2D texture, Vector2 position, float rotation, float scale, Color tint); // Draw a Texture2D with extended parameters -RLAPI void DrawTextureRec(Texture2D texture, Rectangle source, Vector2 position, Color tint); // Draw a part of a texture defined by a rectangle -RLAPI void DrawTexturePro(Texture2D texture, Rectangle source, Rectangle dest, Vector2 origin, float rotation, Color tint); // Draw a part of a texture defined by a rectangle with 'pro' parameters -RLAPI void DrawTextureNPatch(Texture2D texture, NPatchInfo nPatchInfo, Rectangle dest, Vector2 origin, float rotation, Color tint); // Draws a texture (or part of it) that stretches or shrinks nicely - -// Color/pixel related functions -RLAPI bool ColorIsEqual(Color col1, Color col2); // Check if two colors are equal -RLAPI Color Fade(Color color, float alpha); // Get color with alpha applied, alpha goes from 0.0f to 1.0f -RLAPI int ColorToInt(Color color); // Get hexadecimal value for a Color (0xRRGGBBAA) -RLAPI Vector4 ColorNormalize(Color color); // Get Color normalized as float [0..1] -RLAPI Color ColorFromNormalized(Vector4 normalized); // Get Color from normalized values [0..1] -RLAPI Vector3 ColorToHSV(Color color); // Get HSV values for a Color, hue [0..360], saturation/value [0..1] -RLAPI Color ColorFromHSV(float hue, float saturation, float value); // Get a Color from HSV values, hue [0..360], saturation/value [0..1] -RLAPI Color ColorTint(Color color, Color tint); // Get color multiplied with another color -RLAPI Color ColorBrightness(Color color, float factor); // Get color with brightness correction, brightness factor goes from -1.0f to 1.0f -RLAPI Color ColorContrast(Color color, float contrast); // Get color with contrast correction, contrast values between -1.0f and 1.0f -RLAPI Color ColorAlpha(Color color, float alpha); // Get color with alpha applied, alpha goes from 0.0f to 1.0f -RLAPI Color ColorAlphaBlend(Color dst, Color src, Color tint); // Get src alpha-blended into dst color with tint -RLAPI Color ColorLerp(Color color1, Color color2, float factor); // Get color lerp interpolation between two colors, factor [0.0f..1.0f] -RLAPI Color GetColor(unsigned int hexValue); // Get Color structure from hexadecimal value -RLAPI Color GetPixelColor(void *srcPtr, int format); // Get Color from a source pixel pointer of certain format -RLAPI void SetPixelColor(void *dstPtr, Color color, int format); // Set color formatted into destination pixel pointer -RLAPI int GetPixelDataSize(int width, int height, int format); // Get pixel data size in bytes for certain format - -//------------------------------------------------------------------------------------ -// Font Loading and Text Drawing Functions (Module: text) -//------------------------------------------------------------------------------------ - -// Font loading/unloading functions -RLAPI Font GetFontDefault(void); // Get the default Font -RLAPI Font LoadFont(const char *fileName); // Load font from file into GPU memory (VRAM) -RLAPI Font LoadFontEx(const char *fileName, int fontSize, int *codepoints, int codepointCount); // Load font from file with extended parameters, use NULL for codepoints and 0 for codepointCount to load the default character set, font size is provided in pixels height -RLAPI Font LoadFontFromImage(Image image, Color key, int firstChar); // Load font from Image (XNA style) -RLAPI Font LoadFontFromMemory(const char *fileType, const unsigned char *fileData, int dataSize, int fontSize, int *codepoints, int codepointCount); // Load font from memory buffer, fileType refers to extension: i.e. '.ttf' -RLAPI bool IsFontValid(Font font); // Check if a font is valid (font data loaded, WARNING: GPU texture not checked) -RLAPI GlyphInfo *LoadFontData(const unsigned char *fileData, int dataSize, int fontSize, int *codepoints, int codepointCount, int type); // Load font data for further use -RLAPI Image GenImageFontAtlas(const GlyphInfo *glyphs, Rectangle **glyphRecs, int glyphCount, int fontSize, int padding, int packMethod); // Generate image font atlas using chars info -RLAPI void UnloadFontData(GlyphInfo *glyphs, int glyphCount); // Unload font chars info data (RAM) -RLAPI void UnloadFont(Font font); // Unload font from GPU memory (VRAM) -RLAPI bool ExportFontAsCode(Font font, const char *fileName); // Export font as code file, returns true on success - -// Text drawing functions -RLAPI void DrawFPS(int posX, int posY); // Draw current FPS -RLAPI void DrawText(const char *text, int posX, int posY, int fontSize, Color color); // Draw text (using default font) -RLAPI void DrawTextEx(Font font, const char *text, Vector2 position, float fontSize, float spacing, Color tint); // Draw text using font and additional parameters -RLAPI void DrawTextPro(Font font, const char *text, Vector2 position, Vector2 origin, float rotation, float fontSize, float spacing, Color tint); // Draw text using Font and pro parameters (rotation) -RLAPI void DrawTextCodepoint(Font font, int codepoint, Vector2 position, float fontSize, Color tint); // Draw one character (codepoint) -RLAPI void DrawTextCodepoints(Font font, const int *codepoints, int codepointCount, Vector2 position, float fontSize, float spacing, Color tint); // Draw multiple character (codepoint) - -// Text font info functions -RLAPI void SetTextLineSpacing(int spacing); // Set vertical line spacing when drawing with line-breaks -RLAPI int MeasureText(const char *text, int fontSize); // Measure string width for default font -RLAPI Vector2 MeasureTextEx(Font font, const char *text, float fontSize, float spacing); // Measure string size for Font -RLAPI int GetGlyphIndex(Font font, int codepoint); // Get glyph index position in font for a codepoint (unicode character), fallback to '?' if not found -RLAPI GlyphInfo GetGlyphInfo(Font font, int codepoint); // Get glyph font info data for a codepoint (unicode character), fallback to '?' if not found -RLAPI Rectangle GetGlyphAtlasRec(Font font, int codepoint); // Get glyph rectangle in font atlas for a codepoint (unicode character), fallback to '?' if not found - -// Text codepoints management functions (unicode characters) -RLAPI char *LoadUTF8(const int *codepoints, int length); // Load UTF-8 text encoded from codepoints array -RLAPI void UnloadUTF8(char *text); // Unload UTF-8 text encoded from codepoints array -RLAPI int *LoadCodepoints(const char *text, int *count); // Load all codepoints from a UTF-8 text string, codepoints count returned by parameter -RLAPI void UnloadCodepoints(int *codepoints); // Unload codepoints data from memory -RLAPI int GetCodepointCount(const char *text); // Get total number of codepoints in a UTF-8 encoded string -RLAPI int GetCodepoint(const char *text, int *codepointSize); // Get next codepoint in a UTF-8 encoded string, 0x3f('?') is returned on failure -RLAPI int GetCodepointNext(const char *text, int *codepointSize); // Get next codepoint in a UTF-8 encoded string, 0x3f('?') is returned on failure -RLAPI int GetCodepointPrevious(const char *text, int *codepointSize); // Get previous codepoint in a UTF-8 encoded string, 0x3f('?') is returned on failure -RLAPI const char *CodepointToUTF8(int codepoint, int *utf8Size); // Encode one codepoint into UTF-8 byte array (array length returned as parameter) - -// Text strings management functions (no UTF-8 strings, only byte chars) -// NOTE: Some strings allocate memory internally for returned strings, just be careful! -RLAPI int TextCopy(char *dst, const char *src); // Copy one string to another, returns bytes copied -RLAPI bool TextIsEqual(const char *text1, const char *text2); // Check if two text string are equal -RLAPI unsigned int TextLength(const char *text); // Get text length, checks for '\0' ending -RLAPI const char *TextFormat(const char *text, ...); // Text formatting with variables (sprintf() style) -RLAPI const char *TextSubtext(const char *text, int position, int length); // Get a piece of a text string -RLAPI char *TextReplace(const char *text, const char *replace, const char *by); // Replace text string (WARNING: memory must be freed!) -RLAPI char *TextInsert(const char *text, const char *insert, int position); // Insert text in a position (WARNING: memory must be freed!) -RLAPI const char *TextJoin(const char **textList, int count, const char *delimiter); // Join text strings with delimiter -RLAPI const char **TextSplit(const char *text, char delimiter, int *count); // Split text into multiple strings -RLAPI void TextAppend(char *text, const char *append, int *position); // Append text at specific position and move cursor! -RLAPI int TextFindIndex(const char *text, const char *find); // Find first text occurrence within a string -RLAPI const char *TextToUpper(const char *text); // Get upper case version of provided string -RLAPI const char *TextToLower(const char *text); // Get lower case version of provided string -RLAPI const char *TextToPascal(const char *text); // Get Pascal case notation version of provided string -RLAPI const char *TextToSnake(const char *text); // Get Snake case notation version of provided string -RLAPI const char *TextToCamel(const char *text); // Get Camel case notation version of provided string - -RLAPI int TextToInteger(const char *text); // Get integer value from text (negative values not supported) -RLAPI float TextToFloat(const char *text); // Get float value from text (negative values not supported) - -//------------------------------------------------------------------------------------ -// Basic 3d Shapes Drawing Functions (Module: models) -//------------------------------------------------------------------------------------ - -// Basic geometric 3D shapes drawing functions -RLAPI void DrawLine3D(Vector3 startPos, Vector3 endPos, Color color); // Draw a line in 3D world space -RLAPI void DrawPoint3D(Vector3 position, Color color); // Draw a point in 3D space, actually a small line -RLAPI void DrawCircle3D(Vector3 center, float radius, Vector3 rotationAxis, float rotationAngle, Color color); // Draw a circle in 3D world space -RLAPI void DrawTriangle3D(Vector3 v1, Vector3 v2, Vector3 v3, Color color); // Draw a color-filled triangle (vertex in counter-clockwise order!) -RLAPI void DrawTriangleStrip3D(const Vector3 *points, int pointCount, Color color); // Draw a triangle strip defined by points -RLAPI void DrawCube(Vector3 position, float width, float height, float length, Color color); // Draw cube -RLAPI void DrawCubeV(Vector3 position, Vector3 size, Color color); // Draw cube (Vector version) -RLAPI void DrawCubeWires(Vector3 position, float width, float height, float length, Color color); // Draw cube wires -RLAPI void DrawCubeWiresV(Vector3 position, Vector3 size, Color color); // Draw cube wires (Vector version) -RLAPI void DrawSphere(Vector3 centerPos, float radius, Color color); // Draw sphere -RLAPI void DrawSphereEx(Vector3 centerPos, float radius, int rings, int slices, Color color); // Draw sphere with extended parameters -RLAPI void DrawSphereWires(Vector3 centerPos, float radius, int rings, int slices, Color color); // Draw sphere wires -RLAPI void DrawCylinder(Vector3 position, float radiusTop, float radiusBottom, float height, int slices, Color color); // Draw a cylinder/cone -RLAPI void DrawCylinderEx(Vector3 startPos, Vector3 endPos, float startRadius, float endRadius, int sides, Color color); // Draw a cylinder with base at startPos and top at endPos -RLAPI void DrawCylinderWires(Vector3 position, float radiusTop, float radiusBottom, float height, int slices, Color color); // Draw a cylinder/cone wires -RLAPI void DrawCylinderWiresEx(Vector3 startPos, Vector3 endPos, float startRadius, float endRadius, int sides, Color color); // Draw a cylinder wires with base at startPos and top at endPos -RLAPI void DrawCapsule(Vector3 startPos, Vector3 endPos, float radius, int slices, int rings, Color color); // Draw a capsule with the center of its sphere caps at startPos and endPos -RLAPI void DrawCapsuleWires(Vector3 startPos, Vector3 endPos, float radius, int slices, int rings, Color color); // Draw capsule wireframe with the center of its sphere caps at startPos and endPos -RLAPI void DrawPlane(Vector3 centerPos, Vector2 size, Color color); // Draw a plane XZ -RLAPI void DrawRay(Ray ray, Color color); // Draw a ray line -RLAPI void DrawGrid(int slices, float spacing); // Draw a grid (centered at (0, 0, 0)) - -//------------------------------------------------------------------------------------ -// Model 3d Loading and Drawing Functions (Module: models) -//------------------------------------------------------------------------------------ - -// Model management functions -RLAPI Model LoadModel(const char *fileName); // Load model from files (meshes and materials) -RLAPI Model LoadModelFromMesh(Mesh mesh); // Load model from generated mesh (default material) -RLAPI bool IsModelValid(Model model); // Check if a model is valid (loaded in GPU, VAO/VBOs) -RLAPI void UnloadModel(Model model); // Unload model (including meshes) from memory (RAM and/or VRAM) -RLAPI BoundingBox GetModelBoundingBox(Model model); // Compute model bounding box limits (considers all meshes) - -// Model drawing functions -RLAPI void DrawModel(Model model, Vector3 position, float scale, Color tint); // Draw a model (with texture if set) -RLAPI void DrawModelEx(Model model, Vector3 position, Vector3 rotationAxis, float rotationAngle, Vector3 scale, Color tint); // Draw a model with extended parameters -RLAPI void DrawModelWires(Model model, Vector3 position, float scale, Color tint); // Draw a model wires (with texture if set) -RLAPI void DrawModelWiresEx(Model model, Vector3 position, Vector3 rotationAxis, float rotationAngle, Vector3 scale, Color tint); // Draw a model wires (with texture if set) with extended parameters -RLAPI void DrawModelPoints(Model model, Vector3 position, float scale, Color tint); // Draw a model as points -RLAPI void DrawModelPointsEx(Model model, Vector3 position, Vector3 rotationAxis, float rotationAngle, Vector3 scale, Color tint); // Draw a model as points with extended parameters -RLAPI void DrawBoundingBox(BoundingBox box, Color color); // Draw bounding box (wires) -RLAPI void DrawBillboard(Camera camera, Texture2D texture, Vector3 position, float scale, Color tint); // Draw a billboard texture -RLAPI void DrawBillboardRec(Camera camera, Texture2D texture, Rectangle source, Vector3 position, Vector2 size, Color tint); // Draw a billboard texture defined by source -RLAPI void DrawBillboardPro(Camera camera, Texture2D texture, Rectangle source, Vector3 position, Vector3 up, Vector2 size, Vector2 origin, float rotation, Color tint); // Draw a billboard texture defined by source and rotation - -// Mesh management functions -RLAPI void UploadMesh(Mesh *mesh, bool dynamic); // Upload mesh vertex data in GPU and provide VAO/VBO ids -RLAPI void UpdateMeshBuffer(Mesh mesh, int index, const void *data, int dataSize, int offset); // Update mesh vertex data in GPU for a specific buffer index -RLAPI void UnloadMesh(Mesh mesh); // Unload mesh data from CPU and GPU -RLAPI void DrawMesh(Mesh mesh, Material material, Matrix transform); // Draw a 3d mesh with material and transform -RLAPI void DrawMeshInstanced(Mesh mesh, Material material, const Matrix *transforms, int instances); // Draw multiple mesh instances with material and different transforms -RLAPI BoundingBox GetMeshBoundingBox(Mesh mesh); // Compute mesh bounding box limits -RLAPI void GenMeshTangents(Mesh *mesh); // Compute mesh tangents -RLAPI bool ExportMesh(Mesh mesh, const char *fileName); // Export mesh data to file, returns true on success -RLAPI bool ExportMeshAsCode(Mesh mesh, const char *fileName); // Export mesh as code file (.h) defining multiple arrays of vertex attributes - -// Mesh generation functions -RLAPI Mesh GenMeshPoly(int sides, float radius); // Generate polygonal mesh -RLAPI Mesh GenMeshPlane(float width, float length, int resX, int resZ); // Generate plane mesh (with subdivisions) -RLAPI Mesh GenMeshCube(float width, float height, float length); // Generate cuboid mesh -RLAPI Mesh GenMeshSphere(float radius, int rings, int slices); // Generate sphere mesh (standard sphere) -RLAPI Mesh GenMeshHemiSphere(float radius, int rings, int slices); // Generate half-sphere mesh (no bottom cap) -RLAPI Mesh GenMeshCylinder(float radius, float height, int slices); // Generate cylinder mesh -RLAPI Mesh GenMeshCone(float radius, float height, int slices); // Generate cone/pyramid mesh -RLAPI Mesh GenMeshTorus(float radius, float size, int radSeg, int sides); // Generate torus mesh -RLAPI Mesh GenMeshKnot(float radius, float size, int radSeg, int sides); // Generate trefoil knot mesh -RLAPI Mesh GenMeshHeightmap(Image heightmap, Vector3 size); // Generate heightmap mesh from image data -RLAPI Mesh GenMeshCubicmap(Image cubicmap, Vector3 cubeSize); // Generate cubes-based map mesh from image data - -// Material loading/unloading functions -RLAPI Material *LoadMaterials(const char *fileName, int *materialCount); // Load materials from model file -RLAPI Material LoadMaterialDefault(void); // Load default material (Supports: DIFFUSE, SPECULAR, NORMAL maps) -RLAPI bool IsMaterialValid(Material material); // Check if a material is valid (shader assigned, map textures loaded in GPU) -RLAPI void UnloadMaterial(Material material); // Unload material from GPU memory (VRAM) -RLAPI void SetMaterialTexture(Material *material, int mapType, Texture2D texture); // Set texture for a material map type (MATERIAL_MAP_DIFFUSE, MATERIAL_MAP_SPECULAR...) -RLAPI void SetModelMeshMaterial(Model *model, int meshId, int materialId); // Set material for a mesh - -// Model animations loading/unloading functions -RLAPI ModelAnimation *LoadModelAnimations(const char *fileName, int *animCount); // Load model animations from file -RLAPI void UpdateModelAnimation(Model model, ModelAnimation anim, int frame); // Update model animation pose (CPU) -RLAPI void UpdateModelAnimationBones(Model model, ModelAnimation anim, int frame); // Update model animation mesh bone matrices (GPU skinning) -RLAPI void UnloadModelAnimation(ModelAnimation anim); // Unload animation data -RLAPI void UnloadModelAnimations(ModelAnimation *animations, int animCount); // Unload animation array data -RLAPI bool IsModelAnimationValid(Model model, ModelAnimation anim); // Check model animation skeleton match - -// Collision detection functions -RLAPI bool CheckCollisionSpheres(Vector3 center1, float radius1, Vector3 center2, float radius2); // Check collision between two spheres -RLAPI bool CheckCollisionBoxes(BoundingBox box1, BoundingBox box2); // Check collision between two bounding boxes -RLAPI bool CheckCollisionBoxSphere(BoundingBox box, Vector3 center, float radius); // Check collision between box and sphere -RLAPI RayCollision GetRayCollisionSphere(Ray ray, Vector3 center, float radius); // Get collision info between ray and sphere -RLAPI RayCollision GetRayCollisionBox(Ray ray, BoundingBox box); // Get collision info between ray and box -RLAPI RayCollision GetRayCollisionMesh(Ray ray, Mesh mesh, Matrix transform); // Get collision info between ray and mesh -RLAPI RayCollision GetRayCollisionTriangle(Ray ray, Vector3 p1, Vector3 p2, Vector3 p3); // Get collision info between ray and triangle -RLAPI RayCollision GetRayCollisionQuad(Ray ray, Vector3 p1, Vector3 p2, Vector3 p3, Vector3 p4); // Get collision info between ray and quad - -//------------------------------------------------------------------------------------ -// Audio Loading and Playing Functions (Module: audio) -//------------------------------------------------------------------------------------ -typedef void (*AudioCallback)(void *bufferData, unsigned int frames); - -// Audio device management functions -RLAPI void InitAudioDevice(void); // Initialize audio device and context -RLAPI void CloseAudioDevice(void); // Close the audio device and context -RLAPI bool IsAudioDeviceReady(void); // Check if audio device has been initialized successfully -RLAPI void SetMasterVolume(float volume); // Set master volume (listener) -RLAPI float GetMasterVolume(void); // Get master volume (listener) - -// Wave/Sound loading/unloading functions -RLAPI Wave LoadWave(const char *fileName); // Load wave data from file -RLAPI Wave LoadWaveFromMemory(const char *fileType, const unsigned char *fileData, int dataSize); // Load wave from memory buffer, fileType refers to extension: i.e. '.wav' -RLAPI bool IsWaveValid(Wave wave); // Checks if wave data is valid (data loaded and parameters) -RLAPI Sound LoadSound(const char *fileName); // Load sound from file -RLAPI Sound LoadSoundFromWave(Wave wave); // Load sound from wave data -RLAPI Sound LoadSoundAlias(Sound source); // Create a new sound that shares the same sample data as the source sound, does not own the sound data -RLAPI bool IsSoundValid(Sound sound); // Checks if a sound is valid (data loaded and buffers initialized) -RLAPI void UpdateSound(Sound sound, const void *data, int sampleCount); // Update sound buffer with new data -RLAPI void UnloadWave(Wave wave); // Unload wave data -RLAPI void UnloadSound(Sound sound); // Unload sound -RLAPI void UnloadSoundAlias(Sound alias); // Unload a sound alias (does not deallocate sample data) -RLAPI bool ExportWave(Wave wave, const char *fileName); // Export wave data to file, returns true on success -RLAPI bool ExportWaveAsCode(Wave wave, const char *fileName); // Export wave sample data to code (.h), returns true on success - -// Wave/Sound management functions -RLAPI void PlaySound(Sound sound); // Play a sound -RLAPI void StopSound(Sound sound); // Stop playing a sound -RLAPI void PauseSound(Sound sound); // Pause a sound -RLAPI void ResumeSound(Sound sound); // Resume a paused sound -RLAPI bool IsSoundPlaying(Sound sound); // Check if a sound is currently playing -RLAPI void SetSoundVolume(Sound sound, float volume); // Set volume for a sound (1.0 is max level) -RLAPI void SetSoundPitch(Sound sound, float pitch); // Set pitch for a sound (1.0 is base level) -RLAPI void SetSoundPan(Sound sound, float pan); // Set pan for a sound (0.5 is center) -RLAPI Wave WaveCopy(Wave wave); // Copy a wave to a new wave -RLAPI void WaveCrop(Wave *wave, int initFrame, int finalFrame); // Crop a wave to defined frames range -RLAPI void WaveFormat(Wave *wave, int sampleRate, int sampleSize, int channels); // Convert wave data to desired format -RLAPI float *LoadWaveSamples(Wave wave); // Load samples data from wave as a 32bit float data array -RLAPI void UnloadWaveSamples(float *samples); // Unload samples data loaded with LoadWaveSamples() - -// Music management functions -RLAPI Music LoadMusicStream(const char *fileName); // Load music stream from file -RLAPI Music LoadMusicStreamFromMemory(const char *fileType, const unsigned char *data, int dataSize); // Load music stream from data -RLAPI bool IsMusicValid(Music music); // Checks if a music stream is valid (context and buffers initialized) -RLAPI void UnloadMusicStream(Music music); // Unload music stream -RLAPI void PlayMusicStream(Music music); // Start music playing -RLAPI bool IsMusicStreamPlaying(Music music); // Check if music is playing -RLAPI void UpdateMusicStream(Music music); // Updates buffers for music streaming -RLAPI void StopMusicStream(Music music); // Stop music playing -RLAPI void PauseMusicStream(Music music); // Pause music playing -RLAPI void ResumeMusicStream(Music music); // Resume playing paused music -RLAPI void SeekMusicStream(Music music, float position); // Seek music to a position (in seconds) -RLAPI void SetMusicVolume(Music music, float volume); // Set volume for music (1.0 is max level) -RLAPI void SetMusicPitch(Music music, float pitch); // Set pitch for a music (1.0 is base level) -RLAPI void SetMusicPan(Music music, float pan); // Set pan for a music (0.5 is center) -RLAPI float GetMusicTimeLength(Music music); // Get music time length (in seconds) -RLAPI float GetMusicTimePlayed(Music music); // Get current music time played (in seconds) - -// AudioStream management functions -RLAPI AudioStream LoadAudioStream(unsigned int sampleRate, unsigned int sampleSize, unsigned int channels); // Load audio stream (to stream raw audio pcm data) -RLAPI bool IsAudioStreamValid(AudioStream stream); // Checks if an audio stream is valid (buffers initialized) -RLAPI void UnloadAudioStream(AudioStream stream); // Unload audio stream and free memory -RLAPI void UpdateAudioStream(AudioStream stream, const void *data, int frameCount); // Update audio stream buffers with data -RLAPI bool IsAudioStreamProcessed(AudioStream stream); // Check if any audio stream buffers requires refill -RLAPI void PlayAudioStream(AudioStream stream); // Play audio stream -RLAPI void PauseAudioStream(AudioStream stream); // Pause audio stream -RLAPI void ResumeAudioStream(AudioStream stream); // Resume audio stream -RLAPI bool IsAudioStreamPlaying(AudioStream stream); // Check if audio stream is playing -RLAPI void StopAudioStream(AudioStream stream); // Stop audio stream -RLAPI void SetAudioStreamVolume(AudioStream stream, float volume); // Set volume for audio stream (1.0 is max level) -RLAPI void SetAudioStreamPitch(AudioStream stream, float pitch); // Set pitch for audio stream (1.0 is base level) -RLAPI void SetAudioStreamPan(AudioStream stream, float pan); // Set pan for audio stream (0.5 is centered) -RLAPI void SetAudioStreamBufferSizeDefault(int size); // Default size for new audio streams -RLAPI void SetAudioStreamCallback(AudioStream stream, AudioCallback callback); // Audio thread callback to request new data - -RLAPI void AttachAudioStreamProcessor(AudioStream stream, AudioCallback processor); // Attach audio stream processor to stream, receives the samples as 'float' -RLAPI void DetachAudioStreamProcessor(AudioStream stream, AudioCallback processor); // Detach audio stream processor from stream - -RLAPI void AttachAudioMixedProcessor(AudioCallback processor); // Attach audio stream processor to the entire audio pipeline, receives the samples as 'float' -RLAPI void DetachAudioMixedProcessor(AudioCallback processor); // Detach audio stream processor from the entire audio pipeline - -#if defined(__cplusplus) -} -#endif - -#endif // RAYLIB_H diff --git a/third_party/raylib/include/raymath.h b/third_party/raylib/include/raymath.h deleted file mode 100644 index 5b5e4c74ff..0000000000 --- a/third_party/raylib/include/raymath.h +++ /dev/null @@ -1,2949 +0,0 @@ -/********************************************************************************************** -* -* raymath v2.0 - Math functions to work with Vector2, Vector3, Matrix and Quaternions -* -* CONVENTIONS: -* - Matrix structure is defined as row-major (memory layout) but parameters naming AND all -* math operations performed by the library consider the structure as it was column-major -* It is like transposed versions of the matrices are used for all the maths -* It benefits some functions making them cache-friendly and also avoids matrix -* transpositions sometimes required by OpenGL -* Example: In memory order, row0 is [m0 m4 m8 m12] but in semantic math row0 is [m0 m1 m2 m3] -* - Functions are always self-contained, no function use another raymath function inside, -* required code is directly re-implemented inside -* - Functions input parameters are always received by value (2 unavoidable exceptions) -* - Functions use always a "result" variable for return (except C++ operators) -* - Functions are always defined inline -* - Angles are always in radians (DEG2RAD/RAD2DEG macros provided for convenience) -* - No compound literals used to make sure libray is compatible with C++ -* -* CONFIGURATION: -* #define RAYMATH_IMPLEMENTATION -* Generates the implementation of the library into the included file. -* If not defined, the library is in header only mode and can be included in other headers -* or source files without problems. But only ONE file should hold the implementation. -* -* #define RAYMATH_STATIC_INLINE -* Define static inline functions code, so #include header suffices for use. -* This may use up lots of memory. -* -* #define RAYMATH_DISABLE_CPP_OPERATORS -* Disables C++ operator overloads for raymath types. -* -* LICENSE: zlib/libpng -* -* Copyright (c) 2015-2024 Ramon Santamaria (@raysan5) -* -* This software is provided "as-is", without any express or implied warranty. In no event -* will the authors be held liable for any damages arising from the use of this software. -* -* Permission is granted to anyone to use this software for any purpose, including commercial -* applications, and to alter it and redistribute it freely, subject to the following restrictions: -* -* 1. The origin of this software must not be misrepresented; you must not claim that you -* wrote the original software. If you use this software in a product, an acknowledgment -* in the product documentation would be appreciated but is not required. -* -* 2. Altered source versions must be plainly marked as such, and must not be misrepresented -* as being the original software. -* -* 3. This notice may not be removed or altered from any source distribution. -* -**********************************************************************************************/ - -#ifndef RAYMATH_H -#define RAYMATH_H - -#if defined(RAYMATH_IMPLEMENTATION) && defined(RAYMATH_STATIC_INLINE) - #error "Specifying both RAYMATH_IMPLEMENTATION and RAYMATH_STATIC_INLINE is contradictory" -#endif - -// Function specifiers definition -#if defined(RAYMATH_IMPLEMENTATION) - #if defined(_WIN32) && defined(BUILD_LIBTYPE_SHARED) - #define RMAPI __declspec(dllexport) extern inline // We are building raylib as a Win32 shared library (.dll) - #elif defined(BUILD_LIBTYPE_SHARED) - #define RMAPI __attribute__((visibility("default"))) // We are building raylib as a Unix shared library (.so/.dylib) - #elif defined(_WIN32) && defined(USE_LIBTYPE_SHARED) - #define RMAPI __declspec(dllimport) // We are using raylib as a Win32 shared library (.dll) - #else - #define RMAPI extern inline // Provide external definition - #endif -#elif defined(RAYMATH_STATIC_INLINE) - #define RMAPI static inline // Functions may be inlined, no external out-of-line definition -#else - #if defined(__TINYC__) - #define RMAPI static inline // plain inline not supported by tinycc (See issue #435) - #else - #define RMAPI inline // Functions may be inlined or external definition used - #endif -#endif - - -//---------------------------------------------------------------------------------- -// Defines and Macros -//---------------------------------------------------------------------------------- -#ifndef PI - #define PI 3.14159265358979323846f -#endif - -#ifndef EPSILON - #define EPSILON 0.000001f -#endif - -#ifndef DEG2RAD - #define DEG2RAD (PI/180.0f) -#endif - -#ifndef RAD2DEG - #define RAD2DEG (180.0f/PI) -#endif - -// Get float vector for Matrix -#ifndef MatrixToFloat - #define MatrixToFloat(mat) (MatrixToFloatV(mat).v) -#endif - -// Get float vector for Vector3 -#ifndef Vector3ToFloat - #define Vector3ToFloat(vec) (Vector3ToFloatV(vec).v) -#endif - -//---------------------------------------------------------------------------------- -// Types and Structures Definition -//---------------------------------------------------------------------------------- -#if !defined(RL_VECTOR2_TYPE) -// Vector2 type -typedef struct Vector2 { - float x; - float y; -} Vector2; -#define RL_VECTOR2_TYPE -#endif - -#if !defined(RL_VECTOR3_TYPE) -// Vector3 type -typedef struct Vector3 { - float x; - float y; - float z; -} Vector3; -#define RL_VECTOR3_TYPE -#endif - -#if !defined(RL_VECTOR4_TYPE) -// Vector4 type -typedef struct Vector4 { - float x; - float y; - float z; - float w; -} Vector4; -#define RL_VECTOR4_TYPE -#endif - -#if !defined(RL_QUATERNION_TYPE) -// Quaternion type -typedef Vector4 Quaternion; -#define RL_QUATERNION_TYPE -#endif - -#if !defined(RL_MATRIX_TYPE) -// Matrix type (OpenGL style 4x4 - right handed, column major) -typedef struct Matrix { - float m0, m4, m8, m12; // Matrix first row (4 components) - float m1, m5, m9, m13; // Matrix second row (4 components) - float m2, m6, m10, m14; // Matrix third row (4 components) - float m3, m7, m11, m15; // Matrix fourth row (4 components) -} Matrix; -#define RL_MATRIX_TYPE -#endif - -// NOTE: Helper types to be used instead of array return types for *ToFloat functions -typedef struct float3 { - float v[3]; -} float3; - -typedef struct float16 { - float v[16]; -} float16; - -#include // Required for: sinf(), cosf(), tan(), atan2f(), sqrtf(), floor(), fminf(), fmaxf(), fabsf() - -//---------------------------------------------------------------------------------- -// Module Functions Definition - Utils math -//---------------------------------------------------------------------------------- - -// Clamp float value -RMAPI float Clamp(float value, float min, float max) -{ - float result = (value < min)? min : value; - - if (result > max) result = max; - - return result; -} - -// Calculate linear interpolation between two floats -RMAPI float Lerp(float start, float end, float amount) -{ - float result = start + amount*(end - start); - - return result; -} - -// Normalize input value within input range -RMAPI float Normalize(float value, float start, float end) -{ - float result = (value - start)/(end - start); - - return result; -} - -// Remap input value within input range to output range -RMAPI float Remap(float value, float inputStart, float inputEnd, float outputStart, float outputEnd) -{ - float result = (value - inputStart)/(inputEnd - inputStart)*(outputEnd - outputStart) + outputStart; - - return result; -} - -// Wrap input value from min to max -RMAPI float Wrap(float value, float min, float max) -{ - float result = value - (max - min)*floorf((value - min)/(max - min)); - - return result; -} - -// Check whether two given floats are almost equal -RMAPI int FloatEquals(float x, float y) -{ -#if !defined(EPSILON) - #define EPSILON 0.000001f -#endif - - int result = (fabsf(x - y)) <= (EPSILON*fmaxf(1.0f, fmaxf(fabsf(x), fabsf(y)))); - - return result; -} - -//---------------------------------------------------------------------------------- -// Module Functions Definition - Vector2 math -//---------------------------------------------------------------------------------- - -// Vector with components value 0.0f -RMAPI Vector2 Vector2Zero(void) -{ - Vector2 result = { 0.0f, 0.0f }; - - return result; -} - -// Vector with components value 1.0f -RMAPI Vector2 Vector2One(void) -{ - Vector2 result = { 1.0f, 1.0f }; - - return result; -} - -// Add two vectors (v1 + v2) -RMAPI Vector2 Vector2Add(Vector2 v1, Vector2 v2) -{ - Vector2 result = { v1.x + v2.x, v1.y + v2.y }; - - return result; -} - -// Add vector and float value -RMAPI Vector2 Vector2AddValue(Vector2 v, float add) -{ - Vector2 result = { v.x + add, v.y + add }; - - return result; -} - -// Subtract two vectors (v1 - v2) -RMAPI Vector2 Vector2Subtract(Vector2 v1, Vector2 v2) -{ - Vector2 result = { v1.x - v2.x, v1.y - v2.y }; - - return result; -} - -// Subtract vector by float value -RMAPI Vector2 Vector2SubtractValue(Vector2 v, float sub) -{ - Vector2 result = { v.x - sub, v.y - sub }; - - return result; -} - -// Calculate vector length -RMAPI float Vector2Length(Vector2 v) -{ - float result = sqrtf((v.x*v.x) + (v.y*v.y)); - - return result; -} - -// Calculate vector square length -RMAPI float Vector2LengthSqr(Vector2 v) -{ - float result = (v.x*v.x) + (v.y*v.y); - - return result; -} - -// Calculate two vectors dot product -RMAPI float Vector2DotProduct(Vector2 v1, Vector2 v2) -{ - float result = (v1.x*v2.x + v1.y*v2.y); - - return result; -} - -// Calculate two vectors cross product -RMAPI float Vector2CrossProduct(Vector2 v1, Vector2 v2) -{ - float result = (v1.x*v2.y - v1.y*v2.x); - - return result; -} - -// Calculate distance between two vectors -RMAPI float Vector2Distance(Vector2 v1, Vector2 v2) -{ - float result = sqrtf((v1.x - v2.x)*(v1.x - v2.x) + (v1.y - v2.y)*(v1.y - v2.y)); - - return result; -} - -// Calculate square distance between two vectors -RMAPI float Vector2DistanceSqr(Vector2 v1, Vector2 v2) -{ - float result = ((v1.x - v2.x)*(v1.x - v2.x) + (v1.y - v2.y)*(v1.y - v2.y)); - - return result; -} - -// Calculate angle between two vectors -// NOTE: Angle is calculated from origin point (0, 0) -RMAPI float Vector2Angle(Vector2 v1, Vector2 v2) -{ - float result = 0.0f; - - float dot = v1.x*v2.x + v1.y*v2.y; - float det = v1.x*v2.y - v1.y*v2.x; - - result = atan2f(det, dot); - - return result; -} - -// Calculate angle defined by a two vectors line -// NOTE: Parameters need to be normalized -// Current implementation should be aligned with glm::angle -RMAPI float Vector2LineAngle(Vector2 start, Vector2 end) -{ - float result = 0.0f; - - // TODO(10/9/2023): Currently angles move clockwise, determine if this is wanted behavior - result = -atan2f(end.y - start.y, end.x - start.x); - - return result; -} - -// Scale vector (multiply by value) -RMAPI Vector2 Vector2Scale(Vector2 v, float scale) -{ - Vector2 result = { v.x*scale, v.y*scale }; - - return result; -} - -// Multiply vector by vector -RMAPI Vector2 Vector2Multiply(Vector2 v1, Vector2 v2) -{ - Vector2 result = { v1.x*v2.x, v1.y*v2.y }; - - return result; -} - -// Negate vector -RMAPI Vector2 Vector2Negate(Vector2 v) -{ - Vector2 result = { -v.x, -v.y }; - - return result; -} - -// Divide vector by vector -RMAPI Vector2 Vector2Divide(Vector2 v1, Vector2 v2) -{ - Vector2 result = { v1.x/v2.x, v1.y/v2.y }; - - return result; -} - -// Normalize provided vector -RMAPI Vector2 Vector2Normalize(Vector2 v) -{ - Vector2 result = { 0 }; - float length = sqrtf((v.x*v.x) + (v.y*v.y)); - - if (length > 0) - { - float ilength = 1.0f/length; - result.x = v.x*ilength; - result.y = v.y*ilength; - } - - return result; -} - -// Transforms a Vector2 by a given Matrix -RMAPI Vector2 Vector2Transform(Vector2 v, Matrix mat) -{ - Vector2 result = { 0 }; - - float x = v.x; - float y = v.y; - float z = 0; - - result.x = mat.m0*x + mat.m4*y + mat.m8*z + mat.m12; - result.y = mat.m1*x + mat.m5*y + mat.m9*z + mat.m13; - - return result; -} - -// Calculate linear interpolation between two vectors -RMAPI Vector2 Vector2Lerp(Vector2 v1, Vector2 v2, float amount) -{ - Vector2 result = { 0 }; - - result.x = v1.x + amount*(v2.x - v1.x); - result.y = v1.y + amount*(v2.y - v1.y); - - return result; -} - -// Calculate reflected vector to normal -RMAPI Vector2 Vector2Reflect(Vector2 v, Vector2 normal) -{ - Vector2 result = { 0 }; - - float dotProduct = (v.x*normal.x + v.y*normal.y); // Dot product - - result.x = v.x - (2.0f*normal.x)*dotProduct; - result.y = v.y - (2.0f*normal.y)*dotProduct; - - return result; -} - -// Get min value for each pair of components -RMAPI Vector2 Vector2Min(Vector2 v1, Vector2 v2) -{ - Vector2 result = { 0 }; - - result.x = fminf(v1.x, v2.x); - result.y = fminf(v1.y, v2.y); - - return result; -} - -// Get max value for each pair of components -RMAPI Vector2 Vector2Max(Vector2 v1, Vector2 v2) -{ - Vector2 result = { 0 }; - - result.x = fmaxf(v1.x, v2.x); - result.y = fmaxf(v1.y, v2.y); - - return result; -} - -// Rotate vector by angle -RMAPI Vector2 Vector2Rotate(Vector2 v, float angle) -{ - Vector2 result = { 0 }; - - float cosres = cosf(angle); - float sinres = sinf(angle); - - result.x = v.x*cosres - v.y*sinres; - result.y = v.x*sinres + v.y*cosres; - - return result; -} - -// Move Vector towards target -RMAPI Vector2 Vector2MoveTowards(Vector2 v, Vector2 target, float maxDistance) -{ - Vector2 result = { 0 }; - - float dx = target.x - v.x; - float dy = target.y - v.y; - float value = (dx*dx) + (dy*dy); - - if ((value == 0) || ((maxDistance >= 0) && (value <= maxDistance*maxDistance))) return target; - - float dist = sqrtf(value); - - result.x = v.x + dx/dist*maxDistance; - result.y = v.y + dy/dist*maxDistance; - - return result; -} - -// Invert the given vector -RMAPI Vector2 Vector2Invert(Vector2 v) -{ - Vector2 result = { 1.0f/v.x, 1.0f/v.y }; - - return result; -} - -// Clamp the components of the vector between -// min and max values specified by the given vectors -RMAPI Vector2 Vector2Clamp(Vector2 v, Vector2 min, Vector2 max) -{ - Vector2 result = { 0 }; - - result.x = fminf(max.x, fmaxf(min.x, v.x)); - result.y = fminf(max.y, fmaxf(min.y, v.y)); - - return result; -} - -// Clamp the magnitude of the vector between two min and max values -RMAPI Vector2 Vector2ClampValue(Vector2 v, float min, float max) -{ - Vector2 result = v; - - float length = (v.x*v.x) + (v.y*v.y); - if (length > 0.0f) - { - length = sqrtf(length); - - float scale = 1; // By default, 1 as the neutral element. - if (length < min) - { - scale = min/length; - } - else if (length > max) - { - scale = max/length; - } - - result.x = v.x*scale; - result.y = v.y*scale; - } - - return result; -} - -// Check whether two given vectors are almost equal -RMAPI int Vector2Equals(Vector2 p, Vector2 q) -{ -#if !defined(EPSILON) - #define EPSILON 0.000001f -#endif - - int result = ((fabsf(p.x - q.x)) <= (EPSILON*fmaxf(1.0f, fmaxf(fabsf(p.x), fabsf(q.x))))) && - ((fabsf(p.y - q.y)) <= (EPSILON*fmaxf(1.0f, fmaxf(fabsf(p.y), fabsf(q.y))))); - - return result; -} - -// Compute the direction of a refracted ray -// v: normalized direction of the incoming ray -// n: normalized normal vector of the interface of two optical media -// r: ratio of the refractive index of the medium from where the ray comes -// to the refractive index of the medium on the other side of the surface -RMAPI Vector2 Vector2Refract(Vector2 v, Vector2 n, float r) -{ - Vector2 result = { 0 }; - - float dot = v.x*n.x + v.y*n.y; - float d = 1.0f - r*r*(1.0f - dot*dot); - - if (d >= 0.0f) - { - d = sqrtf(d); - v.x = r*v.x - (r*dot + d)*n.x; - v.y = r*v.y - (r*dot + d)*n.y; - - result = v; - } - - return result; -} - - -//---------------------------------------------------------------------------------- -// Module Functions Definition - Vector3 math -//---------------------------------------------------------------------------------- - -// Vector with components value 0.0f -RMAPI Vector3 Vector3Zero(void) -{ - Vector3 result = { 0.0f, 0.0f, 0.0f }; - - return result; -} - -// Vector with components value 1.0f -RMAPI Vector3 Vector3One(void) -{ - Vector3 result = { 1.0f, 1.0f, 1.0f }; - - return result; -} - -// Add two vectors -RMAPI Vector3 Vector3Add(Vector3 v1, Vector3 v2) -{ - Vector3 result = { v1.x + v2.x, v1.y + v2.y, v1.z + v2.z }; - - return result; -} - -// Add vector and float value -RMAPI Vector3 Vector3AddValue(Vector3 v, float add) -{ - Vector3 result = { v.x + add, v.y + add, v.z + add }; - - return result; -} - -// Subtract two vectors -RMAPI Vector3 Vector3Subtract(Vector3 v1, Vector3 v2) -{ - Vector3 result = { v1.x - v2.x, v1.y - v2.y, v1.z - v2.z }; - - return result; -} - -// Subtract vector by float value -RMAPI Vector3 Vector3SubtractValue(Vector3 v, float sub) -{ - Vector3 result = { v.x - sub, v.y - sub, v.z - sub }; - - return result; -} - -// Multiply vector by scalar -RMAPI Vector3 Vector3Scale(Vector3 v, float scalar) -{ - Vector3 result = { v.x*scalar, v.y*scalar, v.z*scalar }; - - return result; -} - -// Multiply vector by vector -RMAPI Vector3 Vector3Multiply(Vector3 v1, Vector3 v2) -{ - Vector3 result = { v1.x*v2.x, v1.y*v2.y, v1.z*v2.z }; - - return result; -} - -// Calculate two vectors cross product -RMAPI Vector3 Vector3CrossProduct(Vector3 v1, Vector3 v2) -{ - Vector3 result = { v1.y*v2.z - v1.z*v2.y, v1.z*v2.x - v1.x*v2.z, v1.x*v2.y - v1.y*v2.x }; - - return result; -} - -// Calculate one vector perpendicular vector -RMAPI Vector3 Vector3Perpendicular(Vector3 v) -{ - Vector3 result = { 0 }; - - float min = fabsf(v.x); - Vector3 cardinalAxis = {1.0f, 0.0f, 0.0f}; - - if (fabsf(v.y) < min) - { - min = fabsf(v.y); - Vector3 tmp = {0.0f, 1.0f, 0.0f}; - cardinalAxis = tmp; - } - - if (fabsf(v.z) < min) - { - Vector3 tmp = {0.0f, 0.0f, 1.0f}; - cardinalAxis = tmp; - } - - // Cross product between vectors - result.x = v.y*cardinalAxis.z - v.z*cardinalAxis.y; - result.y = v.z*cardinalAxis.x - v.x*cardinalAxis.z; - result.z = v.x*cardinalAxis.y - v.y*cardinalAxis.x; - - return result; -} - -// Calculate vector length -RMAPI float Vector3Length(const Vector3 v) -{ - float result = sqrtf(v.x*v.x + v.y*v.y + v.z*v.z); - - return result; -} - -// Calculate vector square length -RMAPI float Vector3LengthSqr(const Vector3 v) -{ - float result = v.x*v.x + v.y*v.y + v.z*v.z; - - return result; -} - -// Calculate two vectors dot product -RMAPI float Vector3DotProduct(Vector3 v1, Vector3 v2) -{ - float result = (v1.x*v2.x + v1.y*v2.y + v1.z*v2.z); - - return result; -} - -// Calculate distance between two vectors -RMAPI float Vector3Distance(Vector3 v1, Vector3 v2) -{ - float result = 0.0f; - - float dx = v2.x - v1.x; - float dy = v2.y - v1.y; - float dz = v2.z - v1.z; - result = sqrtf(dx*dx + dy*dy + dz*dz); - - return result; -} - -// Calculate square distance between two vectors -RMAPI float Vector3DistanceSqr(Vector3 v1, Vector3 v2) -{ - float result = 0.0f; - - float dx = v2.x - v1.x; - float dy = v2.y - v1.y; - float dz = v2.z - v1.z; - result = dx*dx + dy*dy + dz*dz; - - return result; -} - -// Calculate angle between two vectors -RMAPI float Vector3Angle(Vector3 v1, Vector3 v2) -{ - float result = 0.0f; - - Vector3 cross = { v1.y*v2.z - v1.z*v2.y, v1.z*v2.x - v1.x*v2.z, v1.x*v2.y - v1.y*v2.x }; - float len = sqrtf(cross.x*cross.x + cross.y*cross.y + cross.z*cross.z); - float dot = (v1.x*v2.x + v1.y*v2.y + v1.z*v2.z); - result = atan2f(len, dot); - - return result; -} - -// Negate provided vector (invert direction) -RMAPI Vector3 Vector3Negate(Vector3 v) -{ - Vector3 result = { -v.x, -v.y, -v.z }; - - return result; -} - -// Divide vector by vector -RMAPI Vector3 Vector3Divide(Vector3 v1, Vector3 v2) -{ - Vector3 result = { v1.x/v2.x, v1.y/v2.y, v1.z/v2.z }; - - return result; -} - -// Normalize provided vector -RMAPI Vector3 Vector3Normalize(Vector3 v) -{ - Vector3 result = v; - - float length = sqrtf(v.x*v.x + v.y*v.y + v.z*v.z); - if (length != 0.0f) - { - float ilength = 1.0f/length; - - result.x *= ilength; - result.y *= ilength; - result.z *= ilength; - } - - return result; -} - -//Calculate the projection of the vector v1 on to v2 -RMAPI Vector3 Vector3Project(Vector3 v1, Vector3 v2) -{ - Vector3 result = { 0 }; - - float v1dv2 = (v1.x*v2.x + v1.y*v2.y + v1.z*v2.z); - float v2dv2 = (v2.x*v2.x + v2.y*v2.y + v2.z*v2.z); - - float mag = v1dv2/v2dv2; - - result.x = v2.x*mag; - result.y = v2.y*mag; - result.z = v2.z*mag; - - return result; -} - -//Calculate the rejection of the vector v1 on to v2 -RMAPI Vector3 Vector3Reject(Vector3 v1, Vector3 v2) -{ - Vector3 result = { 0 }; - - float v1dv2 = (v1.x*v2.x + v1.y*v2.y + v1.z*v2.z); - float v2dv2 = (v2.x*v2.x + v2.y*v2.y + v2.z*v2.z); - - float mag = v1dv2/v2dv2; - - result.x = v1.x - (v2.x*mag); - result.y = v1.y - (v2.y*mag); - result.z = v1.z - (v2.z*mag); - - return result; -} - -// Orthonormalize provided vectors -// Makes vectors normalized and orthogonal to each other -// Gram-Schmidt function implementation -RMAPI void Vector3OrthoNormalize(Vector3 *v1, Vector3 *v2) -{ - float length = 0.0f; - float ilength = 0.0f; - - // Vector3Normalize(*v1); - Vector3 v = *v1; - length = sqrtf(v.x*v.x + v.y*v.y + v.z*v.z); - if (length == 0.0f) length = 1.0f; - ilength = 1.0f/length; - v1->x *= ilength; - v1->y *= ilength; - v1->z *= ilength; - - // Vector3CrossProduct(*v1, *v2) - Vector3 vn1 = { v1->y*v2->z - v1->z*v2->y, v1->z*v2->x - v1->x*v2->z, v1->x*v2->y - v1->y*v2->x }; - - // Vector3Normalize(vn1); - v = vn1; - length = sqrtf(v.x*v.x + v.y*v.y + v.z*v.z); - if (length == 0.0f) length = 1.0f; - ilength = 1.0f/length; - vn1.x *= ilength; - vn1.y *= ilength; - vn1.z *= ilength; - - // Vector3CrossProduct(vn1, *v1) - Vector3 vn2 = { vn1.y*v1->z - vn1.z*v1->y, vn1.z*v1->x - vn1.x*v1->z, vn1.x*v1->y - vn1.y*v1->x }; - - *v2 = vn2; -} - -// Transforms a Vector3 by a given Matrix -RMAPI Vector3 Vector3Transform(Vector3 v, Matrix mat) -{ - Vector3 result = { 0 }; - - float x = v.x; - float y = v.y; - float z = v.z; - - result.x = mat.m0*x + mat.m4*y + mat.m8*z + mat.m12; - result.y = mat.m1*x + mat.m5*y + mat.m9*z + mat.m13; - result.z = mat.m2*x + mat.m6*y + mat.m10*z + mat.m14; - - return result; -} - -// Transform a vector by quaternion rotation -RMAPI Vector3 Vector3RotateByQuaternion(Vector3 v, Quaternion q) -{ - Vector3 result = { 0 }; - - result.x = v.x*(q.x*q.x + q.w*q.w - q.y*q.y - q.z*q.z) + v.y*(2*q.x*q.y - 2*q.w*q.z) + v.z*(2*q.x*q.z + 2*q.w*q.y); - result.y = v.x*(2*q.w*q.z + 2*q.x*q.y) + v.y*(q.w*q.w - q.x*q.x + q.y*q.y - q.z*q.z) + v.z*(-2*q.w*q.x + 2*q.y*q.z); - result.z = v.x*(-2*q.w*q.y + 2*q.x*q.z) + v.y*(2*q.w*q.x + 2*q.y*q.z)+ v.z*(q.w*q.w - q.x*q.x - q.y*q.y + q.z*q.z); - - return result; -} - -// Rotates a vector around an axis -RMAPI Vector3 Vector3RotateByAxisAngle(Vector3 v, Vector3 axis, float angle) -{ - // Using Euler-Rodrigues Formula - // Ref.: https://en.wikipedia.org/w/index.php?title=Euler%E2%80%93Rodrigues_formula - - Vector3 result = v; - - // Vector3Normalize(axis); - float length = sqrtf(axis.x*axis.x + axis.y*axis.y + axis.z*axis.z); - if (length == 0.0f) length = 1.0f; - float ilength = 1.0f/length; - axis.x *= ilength; - axis.y *= ilength; - axis.z *= ilength; - - angle /= 2.0f; - float a = sinf(angle); - float b = axis.x*a; - float c = axis.y*a; - float d = axis.z*a; - a = cosf(angle); - Vector3 w = { b, c, d }; - - // Vector3CrossProduct(w, v) - Vector3 wv = { w.y*v.z - w.z*v.y, w.z*v.x - w.x*v.z, w.x*v.y - w.y*v.x }; - - // Vector3CrossProduct(w, wv) - Vector3 wwv = { w.y*wv.z - w.z*wv.y, w.z*wv.x - w.x*wv.z, w.x*wv.y - w.y*wv.x }; - - // Vector3Scale(wv, 2*a) - a *= 2; - wv.x *= a; - wv.y *= a; - wv.z *= a; - - // Vector3Scale(wwv, 2) - wwv.x *= 2; - wwv.y *= 2; - wwv.z *= 2; - - result.x += wv.x; - result.y += wv.y; - result.z += wv.z; - - result.x += wwv.x; - result.y += wwv.y; - result.z += wwv.z; - - return result; -} - -// Move Vector towards target -RMAPI Vector3 Vector3MoveTowards(Vector3 v, Vector3 target, float maxDistance) -{ - Vector3 result = { 0 }; - - float dx = target.x - v.x; - float dy = target.y - v.y; - float dz = target.z - v.z; - float value = (dx*dx) + (dy*dy) + (dz*dz); - - if ((value == 0) || ((maxDistance >= 0) && (value <= maxDistance*maxDistance))) return target; - - float dist = sqrtf(value); - - result.x = v.x + dx/dist*maxDistance; - result.y = v.y + dy/dist*maxDistance; - result.z = v.z + dz/dist*maxDistance; - - return result; -} - -// Calculate linear interpolation between two vectors -RMAPI Vector3 Vector3Lerp(Vector3 v1, Vector3 v2, float amount) -{ - Vector3 result = { 0 }; - - result.x = v1.x + amount*(v2.x - v1.x); - result.y = v1.y + amount*(v2.y - v1.y); - result.z = v1.z + amount*(v2.z - v1.z); - - return result; -} - -// Calculate cubic hermite interpolation between two vectors and their tangents -// as described in the GLTF 2.0 specification: https://registry.khronos.org/glTF/specs/2.0/glTF-2.0.html#interpolation-cubic -RMAPI Vector3 Vector3CubicHermite(Vector3 v1, Vector3 tangent1, Vector3 v2, Vector3 tangent2, float amount) -{ - Vector3 result = { 0 }; - - float amountPow2 = amount*amount; - float amountPow3 = amount*amount*amount; - - result.x = (2*amountPow3 - 3*amountPow2 + 1)*v1.x + (amountPow3 - 2*amountPow2 + amount)*tangent1.x + (-2*amountPow3 + 3*amountPow2)*v2.x + (amountPow3 - amountPow2)*tangent2.x; - result.y = (2*amountPow3 - 3*amountPow2 + 1)*v1.y + (amountPow3 - 2*amountPow2 + amount)*tangent1.y + (-2*amountPow3 + 3*amountPow2)*v2.y + (amountPow3 - amountPow2)*tangent2.y; - result.z = (2*amountPow3 - 3*amountPow2 + 1)*v1.z + (amountPow3 - 2*amountPow2 + amount)*tangent1.z + (-2*amountPow3 + 3*amountPow2)*v2.z + (amountPow3 - amountPow2)*tangent2.z; - - return result; -} - -// Calculate reflected vector to normal -RMAPI Vector3 Vector3Reflect(Vector3 v, Vector3 normal) -{ - Vector3 result = { 0 }; - - // I is the original vector - // N is the normal of the incident plane - // R = I - (2*N*(DotProduct[I, N])) - - float dotProduct = (v.x*normal.x + v.y*normal.y + v.z*normal.z); - - result.x = v.x - (2.0f*normal.x)*dotProduct; - result.y = v.y - (2.0f*normal.y)*dotProduct; - result.z = v.z - (2.0f*normal.z)*dotProduct; - - return result; -} - -// Get min value for each pair of components -RMAPI Vector3 Vector3Min(Vector3 v1, Vector3 v2) -{ - Vector3 result = { 0 }; - - result.x = fminf(v1.x, v2.x); - result.y = fminf(v1.y, v2.y); - result.z = fminf(v1.z, v2.z); - - return result; -} - -// Get max value for each pair of components -RMAPI Vector3 Vector3Max(Vector3 v1, Vector3 v2) -{ - Vector3 result = { 0 }; - - result.x = fmaxf(v1.x, v2.x); - result.y = fmaxf(v1.y, v2.y); - result.z = fmaxf(v1.z, v2.z); - - return result; -} - -// Compute barycenter coordinates (u, v, w) for point p with respect to triangle (a, b, c) -// NOTE: Assumes P is on the plane of the triangle -RMAPI Vector3 Vector3Barycenter(Vector3 p, Vector3 a, Vector3 b, Vector3 c) -{ - Vector3 result = { 0 }; - - Vector3 v0 = { b.x - a.x, b.y - a.y, b.z - a.z }; // Vector3Subtract(b, a) - Vector3 v1 = { c.x - a.x, c.y - a.y, c.z - a.z }; // Vector3Subtract(c, a) - Vector3 v2 = { p.x - a.x, p.y - a.y, p.z - a.z }; // Vector3Subtract(p, a) - float d00 = (v0.x*v0.x + v0.y*v0.y + v0.z*v0.z); // Vector3DotProduct(v0, v0) - float d01 = (v0.x*v1.x + v0.y*v1.y + v0.z*v1.z); // Vector3DotProduct(v0, v1) - float d11 = (v1.x*v1.x + v1.y*v1.y + v1.z*v1.z); // Vector3DotProduct(v1, v1) - float d20 = (v2.x*v0.x + v2.y*v0.y + v2.z*v0.z); // Vector3DotProduct(v2, v0) - float d21 = (v2.x*v1.x + v2.y*v1.y + v2.z*v1.z); // Vector3DotProduct(v2, v1) - - float denom = d00*d11 - d01*d01; - - result.y = (d11*d20 - d01*d21)/denom; - result.z = (d00*d21 - d01*d20)/denom; - result.x = 1.0f - (result.z + result.y); - - return result; -} - -// Projects a Vector3 from screen space into object space -// NOTE: We are avoiding calling other raymath functions despite available -RMAPI Vector3 Vector3Unproject(Vector3 source, Matrix projection, Matrix view) -{ - Vector3 result = { 0 }; - - // Calculate unprojected matrix (multiply view matrix by projection matrix) and invert it - Matrix matViewProj = { // MatrixMultiply(view, projection); - view.m0*projection.m0 + view.m1*projection.m4 + view.m2*projection.m8 + view.m3*projection.m12, - view.m0*projection.m1 + view.m1*projection.m5 + view.m2*projection.m9 + view.m3*projection.m13, - view.m0*projection.m2 + view.m1*projection.m6 + view.m2*projection.m10 + view.m3*projection.m14, - view.m0*projection.m3 + view.m1*projection.m7 + view.m2*projection.m11 + view.m3*projection.m15, - view.m4*projection.m0 + view.m5*projection.m4 + view.m6*projection.m8 + view.m7*projection.m12, - view.m4*projection.m1 + view.m5*projection.m5 + view.m6*projection.m9 + view.m7*projection.m13, - view.m4*projection.m2 + view.m5*projection.m6 + view.m6*projection.m10 + view.m7*projection.m14, - view.m4*projection.m3 + view.m5*projection.m7 + view.m6*projection.m11 + view.m7*projection.m15, - view.m8*projection.m0 + view.m9*projection.m4 + view.m10*projection.m8 + view.m11*projection.m12, - view.m8*projection.m1 + view.m9*projection.m5 + view.m10*projection.m9 + view.m11*projection.m13, - view.m8*projection.m2 + view.m9*projection.m6 + view.m10*projection.m10 + view.m11*projection.m14, - view.m8*projection.m3 + view.m9*projection.m7 + view.m10*projection.m11 + view.m11*projection.m15, - view.m12*projection.m0 + view.m13*projection.m4 + view.m14*projection.m8 + view.m15*projection.m12, - view.m12*projection.m1 + view.m13*projection.m5 + view.m14*projection.m9 + view.m15*projection.m13, - view.m12*projection.m2 + view.m13*projection.m6 + view.m14*projection.m10 + view.m15*projection.m14, - view.m12*projection.m3 + view.m13*projection.m7 + view.m14*projection.m11 + view.m15*projection.m15 }; - - // Calculate inverted matrix -> MatrixInvert(matViewProj); - // Cache the matrix values (speed optimization) - float a00 = matViewProj.m0, a01 = matViewProj.m1, a02 = matViewProj.m2, a03 = matViewProj.m3; - float a10 = matViewProj.m4, a11 = matViewProj.m5, a12 = matViewProj.m6, a13 = matViewProj.m7; - float a20 = matViewProj.m8, a21 = matViewProj.m9, a22 = matViewProj.m10, a23 = matViewProj.m11; - float a30 = matViewProj.m12, a31 = matViewProj.m13, a32 = matViewProj.m14, a33 = matViewProj.m15; - - float b00 = a00*a11 - a01*a10; - float b01 = a00*a12 - a02*a10; - float b02 = a00*a13 - a03*a10; - float b03 = a01*a12 - a02*a11; - float b04 = a01*a13 - a03*a11; - float b05 = a02*a13 - a03*a12; - float b06 = a20*a31 - a21*a30; - float b07 = a20*a32 - a22*a30; - float b08 = a20*a33 - a23*a30; - float b09 = a21*a32 - a22*a31; - float b10 = a21*a33 - a23*a31; - float b11 = a22*a33 - a23*a32; - - // Calculate the invert determinant (inlined to avoid double-caching) - float invDet = 1.0f/(b00*b11 - b01*b10 + b02*b09 + b03*b08 - b04*b07 + b05*b06); - - Matrix matViewProjInv = { - (a11*b11 - a12*b10 + a13*b09)*invDet, - (-a01*b11 + a02*b10 - a03*b09)*invDet, - (a31*b05 - a32*b04 + a33*b03)*invDet, - (-a21*b05 + a22*b04 - a23*b03)*invDet, - (-a10*b11 + a12*b08 - a13*b07)*invDet, - (a00*b11 - a02*b08 + a03*b07)*invDet, - (-a30*b05 + a32*b02 - a33*b01)*invDet, - (a20*b05 - a22*b02 + a23*b01)*invDet, - (a10*b10 - a11*b08 + a13*b06)*invDet, - (-a00*b10 + a01*b08 - a03*b06)*invDet, - (a30*b04 - a31*b02 + a33*b00)*invDet, - (-a20*b04 + a21*b02 - a23*b00)*invDet, - (-a10*b09 + a11*b07 - a12*b06)*invDet, - (a00*b09 - a01*b07 + a02*b06)*invDet, - (-a30*b03 + a31*b01 - a32*b00)*invDet, - (a20*b03 - a21*b01 + a22*b00)*invDet }; - - // Create quaternion from source point - Quaternion quat = { source.x, source.y, source.z, 1.0f }; - - // Multiply quat point by unprojecte matrix - Quaternion qtransformed = { // QuaternionTransform(quat, matViewProjInv) - matViewProjInv.m0*quat.x + matViewProjInv.m4*quat.y + matViewProjInv.m8*quat.z + matViewProjInv.m12*quat.w, - matViewProjInv.m1*quat.x + matViewProjInv.m5*quat.y + matViewProjInv.m9*quat.z + matViewProjInv.m13*quat.w, - matViewProjInv.m2*quat.x + matViewProjInv.m6*quat.y + matViewProjInv.m10*quat.z + matViewProjInv.m14*quat.w, - matViewProjInv.m3*quat.x + matViewProjInv.m7*quat.y + matViewProjInv.m11*quat.z + matViewProjInv.m15*quat.w }; - - // Normalized world points in vectors - result.x = qtransformed.x/qtransformed.w; - result.y = qtransformed.y/qtransformed.w; - result.z = qtransformed.z/qtransformed.w; - - return result; -} - -// Get Vector3 as float array -RMAPI float3 Vector3ToFloatV(Vector3 v) -{ - float3 buffer = { 0 }; - - buffer.v[0] = v.x; - buffer.v[1] = v.y; - buffer.v[2] = v.z; - - return buffer; -} - -// Invert the given vector -RMAPI Vector3 Vector3Invert(Vector3 v) -{ - Vector3 result = { 1.0f/v.x, 1.0f/v.y, 1.0f/v.z }; - - return result; -} - -// Clamp the components of the vector between -// min and max values specified by the given vectors -RMAPI Vector3 Vector3Clamp(Vector3 v, Vector3 min, Vector3 max) -{ - Vector3 result = { 0 }; - - result.x = fminf(max.x, fmaxf(min.x, v.x)); - result.y = fminf(max.y, fmaxf(min.y, v.y)); - result.z = fminf(max.z, fmaxf(min.z, v.z)); - - return result; -} - -// Clamp the magnitude of the vector between two values -RMAPI Vector3 Vector3ClampValue(Vector3 v, float min, float max) -{ - Vector3 result = v; - - float length = (v.x*v.x) + (v.y*v.y) + (v.z*v.z); - if (length > 0.0f) - { - length = sqrtf(length); - - float scale = 1; // By default, 1 as the neutral element. - if (length < min) - { - scale = min/length; - } - else if (length > max) - { - scale = max/length; - } - - result.x = v.x*scale; - result.y = v.y*scale; - result.z = v.z*scale; - } - - return result; -} - -// Check whether two given vectors are almost equal -RMAPI int Vector3Equals(Vector3 p, Vector3 q) -{ -#if !defined(EPSILON) - #define EPSILON 0.000001f -#endif - - int result = ((fabsf(p.x - q.x)) <= (EPSILON*fmaxf(1.0f, fmaxf(fabsf(p.x), fabsf(q.x))))) && - ((fabsf(p.y - q.y)) <= (EPSILON*fmaxf(1.0f, fmaxf(fabsf(p.y), fabsf(q.y))))) && - ((fabsf(p.z - q.z)) <= (EPSILON*fmaxf(1.0f, fmaxf(fabsf(p.z), fabsf(q.z))))); - - return result; -} - -// Compute the direction of a refracted ray -// v: normalized direction of the incoming ray -// n: normalized normal vector of the interface of two optical media -// r: ratio of the refractive index of the medium from where the ray comes -// to the refractive index of the medium on the other side of the surface -RMAPI Vector3 Vector3Refract(Vector3 v, Vector3 n, float r) -{ - Vector3 result = { 0 }; - - float dot = v.x*n.x + v.y*n.y + v.z*n.z; - float d = 1.0f - r*r*(1.0f - dot*dot); - - if (d >= 0.0f) - { - d = sqrtf(d); - v.x = r*v.x - (r*dot + d)*n.x; - v.y = r*v.y - (r*dot + d)*n.y; - v.z = r*v.z - (r*dot + d)*n.z; - - result = v; - } - - return result; -} - - -//---------------------------------------------------------------------------------- -// Module Functions Definition - Vector4 math -//---------------------------------------------------------------------------------- - -RMAPI Vector4 Vector4Zero(void) -{ - Vector4 result = { 0.0f, 0.0f, 0.0f, 0.0f }; - return result; -} - -RMAPI Vector4 Vector4One(void) -{ - Vector4 result = { 1.0f, 1.0f, 1.0f, 1.0f }; - return result; -} - -RMAPI Vector4 Vector4Add(Vector4 v1, Vector4 v2) -{ - Vector4 result = { - v1.x + v2.x, - v1.y + v2.y, - v1.z + v2.z, - v1.w + v2.w - }; - return result; -} - -RMAPI Vector4 Vector4AddValue(Vector4 v, float add) -{ - Vector4 result = { - v.x + add, - v.y + add, - v.z + add, - v.w + add - }; - return result; -} - -RMAPI Vector4 Vector4Subtract(Vector4 v1, Vector4 v2) -{ - Vector4 result = { - v1.x - v2.x, - v1.y - v2.y, - v1.z - v2.z, - v1.w - v2.w - }; - return result; -} - -RMAPI Vector4 Vector4SubtractValue(Vector4 v, float add) -{ - Vector4 result = { - v.x - add, - v.y - add, - v.z - add, - v.w - add - }; - return result; -} - -RMAPI float Vector4Length(Vector4 v) -{ - float result = sqrtf((v.x*v.x) + (v.y*v.y) + (v.z*v.z) + (v.w*v.w)); - return result; -} - -RMAPI float Vector4LengthSqr(Vector4 v) -{ - float result = (v.x*v.x) + (v.y*v.y) + (v.z*v.z) + (v.w*v.w); - return result; -} - -RMAPI float Vector4DotProduct(Vector4 v1, Vector4 v2) -{ - float result = (v1.x*v2.x + v1.y*v2.y + v1.z*v2.z + v1.w*v2.w); - return result; -} - -// Calculate distance between two vectors -RMAPI float Vector4Distance(Vector4 v1, Vector4 v2) -{ - float result = sqrtf( - (v1.x - v2.x)*(v1.x - v2.x) + (v1.y - v2.y)*(v1.y - v2.y) + - (v1.z - v2.z)*(v1.z - v2.z) + (v1.w - v2.w)*(v1.w - v2.w)); - return result; -} - -// Calculate square distance between two vectors -RMAPI float Vector4DistanceSqr(Vector4 v1, Vector4 v2) -{ - float result = - (v1.x - v2.x)*(v1.x - v2.x) + (v1.y - v2.y)*(v1.y - v2.y) + - (v1.z - v2.z)*(v1.z - v2.z) + (v1.w - v2.w)*(v1.w - v2.w); - - return result; -} - -RMAPI Vector4 Vector4Scale(Vector4 v, float scale) -{ - Vector4 result = { v.x*scale, v.y*scale, v.z*scale, v.w*scale }; - return result; -} - -// Multiply vector by vector -RMAPI Vector4 Vector4Multiply(Vector4 v1, Vector4 v2) -{ - Vector4 result = { v1.x*v2.x, v1.y*v2.y, v1.z*v2.z, v1.w*v2.w }; - return result; -} - -// Negate vector -RMAPI Vector4 Vector4Negate(Vector4 v) -{ - Vector4 result = { -v.x, -v.y, -v.z, -v.w }; - return result; -} - -// Divide vector by vector -RMAPI Vector4 Vector4Divide(Vector4 v1, Vector4 v2) -{ - Vector4 result = { v1.x/v2.x, v1.y/v2.y, v1.z/v2.z, v1.w/v2.w }; - return result; -} - -// Normalize provided vector -RMAPI Vector4 Vector4Normalize(Vector4 v) -{ - Vector4 result = { 0 }; - float length = sqrtf((v.x*v.x) + (v.y*v.y) + (v.z*v.z) + (v.w*v.w)); - - if (length > 0) - { - float ilength = 1.0f/length; - result.x = v.x*ilength; - result.y = v.y*ilength; - result.z = v.z*ilength; - result.w = v.w*ilength; - } - - return result; -} - -// Get min value for each pair of components -RMAPI Vector4 Vector4Min(Vector4 v1, Vector4 v2) -{ - Vector4 result = { 0 }; - - result.x = fminf(v1.x, v2.x); - result.y = fminf(v1.y, v2.y); - result.z = fminf(v1.z, v2.z); - result.w = fminf(v1.w, v2.w); - - return result; -} - -// Get max value for each pair of components -RMAPI Vector4 Vector4Max(Vector4 v1, Vector4 v2) -{ - Vector4 result = { 0 }; - - result.x = fmaxf(v1.x, v2.x); - result.y = fmaxf(v1.y, v2.y); - result.z = fmaxf(v1.z, v2.z); - result.w = fmaxf(v1.w, v2.w); - - return result; -} - -// Calculate linear interpolation between two vectors -RMAPI Vector4 Vector4Lerp(Vector4 v1, Vector4 v2, float amount) -{ - Vector4 result = { 0 }; - - result.x = v1.x + amount*(v2.x - v1.x); - result.y = v1.y + amount*(v2.y - v1.y); - result.z = v1.z + amount*(v2.z - v1.z); - result.w = v1.w + amount*(v2.w - v1.w); - - return result; -} - -// Move Vector towards target -RMAPI Vector4 Vector4MoveTowards(Vector4 v, Vector4 target, float maxDistance) -{ - Vector4 result = { 0 }; - - float dx = target.x - v.x; - float dy = target.y - v.y; - float dz = target.z - v.z; - float dw = target.w - v.w; - float value = (dx*dx) + (dy*dy) + (dz*dz) + (dw*dw); - - if ((value == 0) || ((maxDistance >= 0) && (value <= maxDistance*maxDistance))) return target; - - float dist = sqrtf(value); - - result.x = v.x + dx/dist*maxDistance; - result.y = v.y + dy/dist*maxDistance; - result.z = v.z + dz/dist*maxDistance; - result.w = v.w + dw/dist*maxDistance; - - return result; -} - -// Invert the given vector -RMAPI Vector4 Vector4Invert(Vector4 v) -{ - Vector4 result = { 1.0f/v.x, 1.0f/v.y, 1.0f/v.z, 1.0f/v.w }; - return result; -} - -// Check whether two given vectors are almost equal -RMAPI int Vector4Equals(Vector4 p, Vector4 q) -{ -#if !defined(EPSILON) - #define EPSILON 0.000001f -#endif - - int result = ((fabsf(p.x - q.x)) <= (EPSILON*fmaxf(1.0f, fmaxf(fabsf(p.x), fabsf(q.x))))) && - ((fabsf(p.y - q.y)) <= (EPSILON*fmaxf(1.0f, fmaxf(fabsf(p.y), fabsf(q.y))))) && - ((fabsf(p.z - q.z)) <= (EPSILON*fmaxf(1.0f, fmaxf(fabsf(p.z), fabsf(q.z))))) && - ((fabsf(p.w - q.w)) <= (EPSILON*fmaxf(1.0f, fmaxf(fabsf(p.w), fabsf(q.w))))); - return result; -} - - -//---------------------------------------------------------------------------------- -// Module Functions Definition - Matrix math -//---------------------------------------------------------------------------------- - -// Compute matrix determinant -RMAPI float MatrixDeterminant(Matrix mat) -{ - float result = 0.0f; - - // Cache the matrix values (speed optimization) - float a00 = mat.m0, a01 = mat.m1, a02 = mat.m2, a03 = mat.m3; - float a10 = mat.m4, a11 = mat.m5, a12 = mat.m6, a13 = mat.m7; - float a20 = mat.m8, a21 = mat.m9, a22 = mat.m10, a23 = mat.m11; - float a30 = mat.m12, a31 = mat.m13, a32 = mat.m14, a33 = mat.m15; - - result = a30*a21*a12*a03 - a20*a31*a12*a03 - a30*a11*a22*a03 + a10*a31*a22*a03 + - a20*a11*a32*a03 - a10*a21*a32*a03 - a30*a21*a02*a13 + a20*a31*a02*a13 + - a30*a01*a22*a13 - a00*a31*a22*a13 - a20*a01*a32*a13 + a00*a21*a32*a13 + - a30*a11*a02*a23 - a10*a31*a02*a23 - a30*a01*a12*a23 + a00*a31*a12*a23 + - a10*a01*a32*a23 - a00*a11*a32*a23 - a20*a11*a02*a33 + a10*a21*a02*a33 + - a20*a01*a12*a33 - a00*a21*a12*a33 - a10*a01*a22*a33 + a00*a11*a22*a33; - - return result; -} - -// Get the trace of the matrix (sum of the values along the diagonal) -RMAPI float MatrixTrace(Matrix mat) -{ - float result = (mat.m0 + mat.m5 + mat.m10 + mat.m15); - - return result; -} - -// Transposes provided matrix -RMAPI Matrix MatrixTranspose(Matrix mat) -{ - Matrix result = { 0 }; - - result.m0 = mat.m0; - result.m1 = mat.m4; - result.m2 = mat.m8; - result.m3 = mat.m12; - result.m4 = mat.m1; - result.m5 = mat.m5; - result.m6 = mat.m9; - result.m7 = mat.m13; - result.m8 = mat.m2; - result.m9 = mat.m6; - result.m10 = mat.m10; - result.m11 = mat.m14; - result.m12 = mat.m3; - result.m13 = mat.m7; - result.m14 = mat.m11; - result.m15 = mat.m15; - - return result; -} - -// Invert provided matrix -RMAPI Matrix MatrixInvert(Matrix mat) -{ - Matrix result = { 0 }; - - // Cache the matrix values (speed optimization) - float a00 = mat.m0, a01 = mat.m1, a02 = mat.m2, a03 = mat.m3; - float a10 = mat.m4, a11 = mat.m5, a12 = mat.m6, a13 = mat.m7; - float a20 = mat.m8, a21 = mat.m9, a22 = mat.m10, a23 = mat.m11; - float a30 = mat.m12, a31 = mat.m13, a32 = mat.m14, a33 = mat.m15; - - float b00 = a00*a11 - a01*a10; - float b01 = a00*a12 - a02*a10; - float b02 = a00*a13 - a03*a10; - float b03 = a01*a12 - a02*a11; - float b04 = a01*a13 - a03*a11; - float b05 = a02*a13 - a03*a12; - float b06 = a20*a31 - a21*a30; - float b07 = a20*a32 - a22*a30; - float b08 = a20*a33 - a23*a30; - float b09 = a21*a32 - a22*a31; - float b10 = a21*a33 - a23*a31; - float b11 = a22*a33 - a23*a32; - - // Calculate the invert determinant (inlined to avoid double-caching) - float invDet = 1.0f/(b00*b11 - b01*b10 + b02*b09 + b03*b08 - b04*b07 + b05*b06); - - result.m0 = (a11*b11 - a12*b10 + a13*b09)*invDet; - result.m1 = (-a01*b11 + a02*b10 - a03*b09)*invDet; - result.m2 = (a31*b05 - a32*b04 + a33*b03)*invDet; - result.m3 = (-a21*b05 + a22*b04 - a23*b03)*invDet; - result.m4 = (-a10*b11 + a12*b08 - a13*b07)*invDet; - result.m5 = (a00*b11 - a02*b08 + a03*b07)*invDet; - result.m6 = (-a30*b05 + a32*b02 - a33*b01)*invDet; - result.m7 = (a20*b05 - a22*b02 + a23*b01)*invDet; - result.m8 = (a10*b10 - a11*b08 + a13*b06)*invDet; - result.m9 = (-a00*b10 + a01*b08 - a03*b06)*invDet; - result.m10 = (a30*b04 - a31*b02 + a33*b00)*invDet; - result.m11 = (-a20*b04 + a21*b02 - a23*b00)*invDet; - result.m12 = (-a10*b09 + a11*b07 - a12*b06)*invDet; - result.m13 = (a00*b09 - a01*b07 + a02*b06)*invDet; - result.m14 = (-a30*b03 + a31*b01 - a32*b00)*invDet; - result.m15 = (a20*b03 - a21*b01 + a22*b00)*invDet; - - return result; -} - -// Get identity matrix -RMAPI Matrix MatrixIdentity(void) -{ - Matrix result = { 1.0f, 0.0f, 0.0f, 0.0f, - 0.0f, 1.0f, 0.0f, 0.0f, - 0.0f, 0.0f, 1.0f, 0.0f, - 0.0f, 0.0f, 0.0f, 1.0f }; - - return result; -} - -// Add two matrices -RMAPI Matrix MatrixAdd(Matrix left, Matrix right) -{ - Matrix result = { 0 }; - - result.m0 = left.m0 + right.m0; - result.m1 = left.m1 + right.m1; - result.m2 = left.m2 + right.m2; - result.m3 = left.m3 + right.m3; - result.m4 = left.m4 + right.m4; - result.m5 = left.m5 + right.m5; - result.m6 = left.m6 + right.m6; - result.m7 = left.m7 + right.m7; - result.m8 = left.m8 + right.m8; - result.m9 = left.m9 + right.m9; - result.m10 = left.m10 + right.m10; - result.m11 = left.m11 + right.m11; - result.m12 = left.m12 + right.m12; - result.m13 = left.m13 + right.m13; - result.m14 = left.m14 + right.m14; - result.m15 = left.m15 + right.m15; - - return result; -} - -// Subtract two matrices (left - right) -RMAPI Matrix MatrixSubtract(Matrix left, Matrix right) -{ - Matrix result = { 0 }; - - result.m0 = left.m0 - right.m0; - result.m1 = left.m1 - right.m1; - result.m2 = left.m2 - right.m2; - result.m3 = left.m3 - right.m3; - result.m4 = left.m4 - right.m4; - result.m5 = left.m5 - right.m5; - result.m6 = left.m6 - right.m6; - result.m7 = left.m7 - right.m7; - result.m8 = left.m8 - right.m8; - result.m9 = left.m9 - right.m9; - result.m10 = left.m10 - right.m10; - result.m11 = left.m11 - right.m11; - result.m12 = left.m12 - right.m12; - result.m13 = left.m13 - right.m13; - result.m14 = left.m14 - right.m14; - result.m15 = left.m15 - right.m15; - - return result; -} - -// Get two matrix multiplication -// NOTE: When multiplying matrices... the order matters! -RMAPI Matrix MatrixMultiply(Matrix left, Matrix right) -{ - Matrix result = { 0 }; - - result.m0 = left.m0*right.m0 + left.m1*right.m4 + left.m2*right.m8 + left.m3*right.m12; - result.m1 = left.m0*right.m1 + left.m1*right.m5 + left.m2*right.m9 + left.m3*right.m13; - result.m2 = left.m0*right.m2 + left.m1*right.m6 + left.m2*right.m10 + left.m3*right.m14; - result.m3 = left.m0*right.m3 + left.m1*right.m7 + left.m2*right.m11 + left.m3*right.m15; - result.m4 = left.m4*right.m0 + left.m5*right.m4 + left.m6*right.m8 + left.m7*right.m12; - result.m5 = left.m4*right.m1 + left.m5*right.m5 + left.m6*right.m9 + left.m7*right.m13; - result.m6 = left.m4*right.m2 + left.m5*right.m6 + left.m6*right.m10 + left.m7*right.m14; - result.m7 = left.m4*right.m3 + left.m5*right.m7 + left.m6*right.m11 + left.m7*right.m15; - result.m8 = left.m8*right.m0 + left.m9*right.m4 + left.m10*right.m8 + left.m11*right.m12; - result.m9 = left.m8*right.m1 + left.m9*right.m5 + left.m10*right.m9 + left.m11*right.m13; - result.m10 = left.m8*right.m2 + left.m9*right.m6 + left.m10*right.m10 + left.m11*right.m14; - result.m11 = left.m8*right.m3 + left.m9*right.m7 + left.m10*right.m11 + left.m11*right.m15; - result.m12 = left.m12*right.m0 + left.m13*right.m4 + left.m14*right.m8 + left.m15*right.m12; - result.m13 = left.m12*right.m1 + left.m13*right.m5 + left.m14*right.m9 + left.m15*right.m13; - result.m14 = left.m12*right.m2 + left.m13*right.m6 + left.m14*right.m10 + left.m15*right.m14; - result.m15 = left.m12*right.m3 + left.m13*right.m7 + left.m14*right.m11 + left.m15*right.m15; - - return result; -} - -// Get translation matrix -RMAPI Matrix MatrixTranslate(float x, float y, float z) -{ - Matrix result = { 1.0f, 0.0f, 0.0f, x, - 0.0f, 1.0f, 0.0f, y, - 0.0f, 0.0f, 1.0f, z, - 0.0f, 0.0f, 0.0f, 1.0f }; - - return result; -} - -// Create rotation matrix from axis and angle -// NOTE: Angle should be provided in radians -RMAPI Matrix MatrixRotate(Vector3 axis, float angle) -{ - Matrix result = { 0 }; - - float x = axis.x, y = axis.y, z = axis.z; - - float lengthSquared = x*x + y*y + z*z; - - if ((lengthSquared != 1.0f) && (lengthSquared != 0.0f)) - { - float ilength = 1.0f/sqrtf(lengthSquared); - x *= ilength; - y *= ilength; - z *= ilength; - } - - float sinres = sinf(angle); - float cosres = cosf(angle); - float t = 1.0f - cosres; - - result.m0 = x*x*t + cosres; - result.m1 = y*x*t + z*sinres; - result.m2 = z*x*t - y*sinres; - result.m3 = 0.0f; - - result.m4 = x*y*t - z*sinres; - result.m5 = y*y*t + cosres; - result.m6 = z*y*t + x*sinres; - result.m7 = 0.0f; - - result.m8 = x*z*t + y*sinres; - result.m9 = y*z*t - x*sinres; - result.m10 = z*z*t + cosres; - result.m11 = 0.0f; - - result.m12 = 0.0f; - result.m13 = 0.0f; - result.m14 = 0.0f; - result.m15 = 1.0f; - - return result; -} - -// Get x-rotation matrix -// NOTE: Angle must be provided in radians -RMAPI Matrix MatrixRotateX(float angle) -{ - Matrix result = { 1.0f, 0.0f, 0.0f, 0.0f, - 0.0f, 1.0f, 0.0f, 0.0f, - 0.0f, 0.0f, 1.0f, 0.0f, - 0.0f, 0.0f, 0.0f, 1.0f }; // MatrixIdentity() - - float cosres = cosf(angle); - float sinres = sinf(angle); - - result.m5 = cosres; - result.m6 = sinres; - result.m9 = -sinres; - result.m10 = cosres; - - return result; -} - -// Get y-rotation matrix -// NOTE: Angle must be provided in radians -RMAPI Matrix MatrixRotateY(float angle) -{ - Matrix result = { 1.0f, 0.0f, 0.0f, 0.0f, - 0.0f, 1.0f, 0.0f, 0.0f, - 0.0f, 0.0f, 1.0f, 0.0f, - 0.0f, 0.0f, 0.0f, 1.0f }; // MatrixIdentity() - - float cosres = cosf(angle); - float sinres = sinf(angle); - - result.m0 = cosres; - result.m2 = -sinres; - result.m8 = sinres; - result.m10 = cosres; - - return result; -} - -// Get z-rotation matrix -// NOTE: Angle must be provided in radians -RMAPI Matrix MatrixRotateZ(float angle) -{ - Matrix result = { 1.0f, 0.0f, 0.0f, 0.0f, - 0.0f, 1.0f, 0.0f, 0.0f, - 0.0f, 0.0f, 1.0f, 0.0f, - 0.0f, 0.0f, 0.0f, 1.0f }; // MatrixIdentity() - - float cosres = cosf(angle); - float sinres = sinf(angle); - - result.m0 = cosres; - result.m1 = sinres; - result.m4 = -sinres; - result.m5 = cosres; - - return result; -} - - -// Get xyz-rotation matrix -// NOTE: Angle must be provided in radians -RMAPI Matrix MatrixRotateXYZ(Vector3 angle) -{ - Matrix result = { 1.0f, 0.0f, 0.0f, 0.0f, - 0.0f, 1.0f, 0.0f, 0.0f, - 0.0f, 0.0f, 1.0f, 0.0f, - 0.0f, 0.0f, 0.0f, 1.0f }; // MatrixIdentity() - - float cosz = cosf(-angle.z); - float sinz = sinf(-angle.z); - float cosy = cosf(-angle.y); - float siny = sinf(-angle.y); - float cosx = cosf(-angle.x); - float sinx = sinf(-angle.x); - - result.m0 = cosz*cosy; - result.m1 = (cosz*siny*sinx) - (sinz*cosx); - result.m2 = (cosz*siny*cosx) + (sinz*sinx); - - result.m4 = sinz*cosy; - result.m5 = (sinz*siny*sinx) + (cosz*cosx); - result.m6 = (sinz*siny*cosx) - (cosz*sinx); - - result.m8 = -siny; - result.m9 = cosy*sinx; - result.m10= cosy*cosx; - - return result; -} - -// Get zyx-rotation matrix -// NOTE: Angle must be provided in radians -RMAPI Matrix MatrixRotateZYX(Vector3 angle) -{ - Matrix result = { 0 }; - - float cz = cosf(angle.z); - float sz = sinf(angle.z); - float cy = cosf(angle.y); - float sy = sinf(angle.y); - float cx = cosf(angle.x); - float sx = sinf(angle.x); - - result.m0 = cz*cy; - result.m4 = cz*sy*sx - cx*sz; - result.m8 = sz*sx + cz*cx*sy; - result.m12 = 0; - - result.m1 = cy*sz; - result.m5 = cz*cx + sz*sy*sx; - result.m9 = cx*sz*sy - cz*sx; - result.m13 = 0; - - result.m2 = -sy; - result.m6 = cy*sx; - result.m10 = cy*cx; - result.m14 = 0; - - result.m3 = 0; - result.m7 = 0; - result.m11 = 0; - result.m15 = 1; - - return result; -} - -// Get scaling matrix -RMAPI Matrix MatrixScale(float x, float y, float z) -{ - Matrix result = { x, 0.0f, 0.0f, 0.0f, - 0.0f, y, 0.0f, 0.0f, - 0.0f, 0.0f, z, 0.0f, - 0.0f, 0.0f, 0.0f, 1.0f }; - - return result; -} - -// Get perspective projection matrix -RMAPI Matrix MatrixFrustum(double left, double right, double bottom, double top, double nearPlane, double farPlane) -{ - Matrix result = { 0 }; - - float rl = (float)(right - left); - float tb = (float)(top - bottom); - float fn = (float)(farPlane - nearPlane); - - result.m0 = ((float)nearPlane*2.0f)/rl; - result.m1 = 0.0f; - result.m2 = 0.0f; - result.m3 = 0.0f; - - result.m4 = 0.0f; - result.m5 = ((float)nearPlane*2.0f)/tb; - result.m6 = 0.0f; - result.m7 = 0.0f; - - result.m8 = ((float)right + (float)left)/rl; - result.m9 = ((float)top + (float)bottom)/tb; - result.m10 = -((float)farPlane + (float)nearPlane)/fn; - result.m11 = -1.0f; - - result.m12 = 0.0f; - result.m13 = 0.0f; - result.m14 = -((float)farPlane*(float)nearPlane*2.0f)/fn; - result.m15 = 0.0f; - - return result; -} - -// Get perspective projection matrix -// NOTE: Fovy angle must be provided in radians -RMAPI Matrix MatrixPerspective(double fovY, double aspect, double nearPlane, double farPlane) -{ - Matrix result = { 0 }; - - double top = nearPlane*tan(fovY*0.5); - double bottom = -top; - double right = top*aspect; - double left = -right; - - // MatrixFrustum(-right, right, -top, top, near, far); - float rl = (float)(right - left); - float tb = (float)(top - bottom); - float fn = (float)(farPlane - nearPlane); - - result.m0 = ((float)nearPlane*2.0f)/rl; - result.m5 = ((float)nearPlane*2.0f)/tb; - result.m8 = ((float)right + (float)left)/rl; - result.m9 = ((float)top + (float)bottom)/tb; - result.m10 = -((float)farPlane + (float)nearPlane)/fn; - result.m11 = -1.0f; - result.m14 = -((float)farPlane*(float)nearPlane*2.0f)/fn; - - return result; -} - -// Get orthographic projection matrix -RMAPI Matrix MatrixOrtho(double left, double right, double bottom, double top, double nearPlane, double farPlane) -{ - Matrix result = { 0 }; - - float rl = (float)(right - left); - float tb = (float)(top - bottom); - float fn = (float)(farPlane - nearPlane); - - result.m0 = 2.0f/rl; - result.m1 = 0.0f; - result.m2 = 0.0f; - result.m3 = 0.0f; - result.m4 = 0.0f; - result.m5 = 2.0f/tb; - result.m6 = 0.0f; - result.m7 = 0.0f; - result.m8 = 0.0f; - result.m9 = 0.0f; - result.m10 = -2.0f/fn; - result.m11 = 0.0f; - result.m12 = -((float)left + (float)right)/rl; - result.m13 = -((float)top + (float)bottom)/tb; - result.m14 = -((float)farPlane + (float)nearPlane)/fn; - result.m15 = 1.0f; - - return result; -} - -// Get camera look-at matrix (view matrix) -RMAPI Matrix MatrixLookAt(Vector3 eye, Vector3 target, Vector3 up) -{ - Matrix result = { 0 }; - - float length = 0.0f; - float ilength = 0.0f; - - // Vector3Subtract(eye, target) - Vector3 vz = { eye.x - target.x, eye.y - target.y, eye.z - target.z }; - - // Vector3Normalize(vz) - Vector3 v = vz; - length = sqrtf(v.x*v.x + v.y*v.y + v.z*v.z); - if (length == 0.0f) length = 1.0f; - ilength = 1.0f/length; - vz.x *= ilength; - vz.y *= ilength; - vz.z *= ilength; - - // Vector3CrossProduct(up, vz) - Vector3 vx = { up.y*vz.z - up.z*vz.y, up.z*vz.x - up.x*vz.z, up.x*vz.y - up.y*vz.x }; - - // Vector3Normalize(x) - v = vx; - length = sqrtf(v.x*v.x + v.y*v.y + v.z*v.z); - if (length == 0.0f) length = 1.0f; - ilength = 1.0f/length; - vx.x *= ilength; - vx.y *= ilength; - vx.z *= ilength; - - // Vector3CrossProduct(vz, vx) - Vector3 vy = { vz.y*vx.z - vz.z*vx.y, vz.z*vx.x - vz.x*vx.z, vz.x*vx.y - vz.y*vx.x }; - - result.m0 = vx.x; - result.m1 = vy.x; - result.m2 = vz.x; - result.m3 = 0.0f; - result.m4 = vx.y; - result.m5 = vy.y; - result.m6 = vz.y; - result.m7 = 0.0f; - result.m8 = vx.z; - result.m9 = vy.z; - result.m10 = vz.z; - result.m11 = 0.0f; - result.m12 = -(vx.x*eye.x + vx.y*eye.y + vx.z*eye.z); // Vector3DotProduct(vx, eye) - result.m13 = -(vy.x*eye.x + vy.y*eye.y + vy.z*eye.z); // Vector3DotProduct(vy, eye) - result.m14 = -(vz.x*eye.x + vz.y*eye.y + vz.z*eye.z); // Vector3DotProduct(vz, eye) - result.m15 = 1.0f; - - return result; -} - -// Get float array of matrix data -RMAPI float16 MatrixToFloatV(Matrix mat) -{ - float16 result = { 0 }; - - result.v[0] = mat.m0; - result.v[1] = mat.m1; - result.v[2] = mat.m2; - result.v[3] = mat.m3; - result.v[4] = mat.m4; - result.v[5] = mat.m5; - result.v[6] = mat.m6; - result.v[7] = mat.m7; - result.v[8] = mat.m8; - result.v[9] = mat.m9; - result.v[10] = mat.m10; - result.v[11] = mat.m11; - result.v[12] = mat.m12; - result.v[13] = mat.m13; - result.v[14] = mat.m14; - result.v[15] = mat.m15; - - return result; -} - -//---------------------------------------------------------------------------------- -// Module Functions Definition - Quaternion math -//---------------------------------------------------------------------------------- - -// Add two quaternions -RMAPI Quaternion QuaternionAdd(Quaternion q1, Quaternion q2) -{ - Quaternion result = {q1.x + q2.x, q1.y + q2.y, q1.z + q2.z, q1.w + q2.w}; - - return result; -} - -// Add quaternion and float value -RMAPI Quaternion QuaternionAddValue(Quaternion q, float add) -{ - Quaternion result = {q.x + add, q.y + add, q.z + add, q.w + add}; - - return result; -} - -// Subtract two quaternions -RMAPI Quaternion QuaternionSubtract(Quaternion q1, Quaternion q2) -{ - Quaternion result = {q1.x - q2.x, q1.y - q2.y, q1.z - q2.z, q1.w - q2.w}; - - return result; -} - -// Subtract quaternion and float value -RMAPI Quaternion QuaternionSubtractValue(Quaternion q, float sub) -{ - Quaternion result = {q.x - sub, q.y - sub, q.z - sub, q.w - sub}; - - return result; -} - -// Get identity quaternion -RMAPI Quaternion QuaternionIdentity(void) -{ - Quaternion result = { 0.0f, 0.0f, 0.0f, 1.0f }; - - return result; -} - -// Computes the length of a quaternion -RMAPI float QuaternionLength(Quaternion q) -{ - float result = sqrtf(q.x*q.x + q.y*q.y + q.z*q.z + q.w*q.w); - - return result; -} - -// Normalize provided quaternion -RMAPI Quaternion QuaternionNormalize(Quaternion q) -{ - Quaternion result = { 0 }; - - float length = sqrtf(q.x*q.x + q.y*q.y + q.z*q.z + q.w*q.w); - if (length == 0.0f) length = 1.0f; - float ilength = 1.0f/length; - - result.x = q.x*ilength; - result.y = q.y*ilength; - result.z = q.z*ilength; - result.w = q.w*ilength; - - return result; -} - -// Invert provided quaternion -RMAPI Quaternion QuaternionInvert(Quaternion q) -{ - Quaternion result = q; - - float lengthSq = q.x*q.x + q.y*q.y + q.z*q.z + q.w*q.w; - - if (lengthSq != 0.0f) - { - float invLength = 1.0f/lengthSq; - - result.x *= -invLength; - result.y *= -invLength; - result.z *= -invLength; - result.w *= invLength; - } - - return result; -} - -// Calculate two quaternion multiplication -RMAPI Quaternion QuaternionMultiply(Quaternion q1, Quaternion q2) -{ - Quaternion result = { 0 }; - - float qax = q1.x, qay = q1.y, qaz = q1.z, qaw = q1.w; - float qbx = q2.x, qby = q2.y, qbz = q2.z, qbw = q2.w; - - result.x = qax*qbw + qaw*qbx + qay*qbz - qaz*qby; - result.y = qay*qbw + qaw*qby + qaz*qbx - qax*qbz; - result.z = qaz*qbw + qaw*qbz + qax*qby - qay*qbx; - result.w = qaw*qbw - qax*qbx - qay*qby - qaz*qbz; - - return result; -} - -// Scale quaternion by float value -RMAPI Quaternion QuaternionScale(Quaternion q, float mul) -{ - Quaternion result = { 0 }; - - result.x = q.x*mul; - result.y = q.y*mul; - result.z = q.z*mul; - result.w = q.w*mul; - - return result; -} - -// Divide two quaternions -RMAPI Quaternion QuaternionDivide(Quaternion q1, Quaternion q2) -{ - Quaternion result = { q1.x/q2.x, q1.y/q2.y, q1.z/q2.z, q1.w/q2.w }; - - return result; -} - -// Calculate linear interpolation between two quaternions -RMAPI Quaternion QuaternionLerp(Quaternion q1, Quaternion q2, float amount) -{ - Quaternion result = { 0 }; - - result.x = q1.x + amount*(q2.x - q1.x); - result.y = q1.y + amount*(q2.y - q1.y); - result.z = q1.z + amount*(q2.z - q1.z); - result.w = q1.w + amount*(q2.w - q1.w); - - return result; -} - -// Calculate slerp-optimized interpolation between two quaternions -RMAPI Quaternion QuaternionNlerp(Quaternion q1, Quaternion q2, float amount) -{ - Quaternion result = { 0 }; - - // QuaternionLerp(q1, q2, amount) - result.x = q1.x + amount*(q2.x - q1.x); - result.y = q1.y + amount*(q2.y - q1.y); - result.z = q1.z + amount*(q2.z - q1.z); - result.w = q1.w + amount*(q2.w - q1.w); - - // QuaternionNormalize(q); - Quaternion q = result; - float length = sqrtf(q.x*q.x + q.y*q.y + q.z*q.z + q.w*q.w); - if (length == 0.0f) length = 1.0f; - float ilength = 1.0f/length; - - result.x = q.x*ilength; - result.y = q.y*ilength; - result.z = q.z*ilength; - result.w = q.w*ilength; - - return result; -} - -// Calculates spherical linear interpolation between two quaternions -RMAPI Quaternion QuaternionSlerp(Quaternion q1, Quaternion q2, float amount) -{ - Quaternion result = { 0 }; - -#if !defined(EPSILON) - #define EPSILON 0.000001f -#endif - - float cosHalfTheta = q1.x*q2.x + q1.y*q2.y + q1.z*q2.z + q1.w*q2.w; - - if (cosHalfTheta < 0) - { - q2.x = -q2.x; q2.y = -q2.y; q2.z = -q2.z; q2.w = -q2.w; - cosHalfTheta = -cosHalfTheta; - } - - if (fabsf(cosHalfTheta) >= 1.0f) result = q1; - else if (cosHalfTheta > 0.95f) result = QuaternionNlerp(q1, q2, amount); - else - { - float halfTheta = acosf(cosHalfTheta); - float sinHalfTheta = sqrtf(1.0f - cosHalfTheta*cosHalfTheta); - - if (fabsf(sinHalfTheta) < EPSILON) - { - result.x = (q1.x*0.5f + q2.x*0.5f); - result.y = (q1.y*0.5f + q2.y*0.5f); - result.z = (q1.z*0.5f + q2.z*0.5f); - result.w = (q1.w*0.5f + q2.w*0.5f); - } - else - { - float ratioA = sinf((1 - amount)*halfTheta)/sinHalfTheta; - float ratioB = sinf(amount*halfTheta)/sinHalfTheta; - - result.x = (q1.x*ratioA + q2.x*ratioB); - result.y = (q1.y*ratioA + q2.y*ratioB); - result.z = (q1.z*ratioA + q2.z*ratioB); - result.w = (q1.w*ratioA + q2.w*ratioB); - } - } - - return result; -} - -// Calculate quaternion cubic spline interpolation using Cubic Hermite Spline algorithm -// as described in the GLTF 2.0 specification: https://registry.khronos.org/glTF/specs/2.0/glTF-2.0.html#interpolation-cubic -RMAPI Quaternion QuaternionCubicHermiteSpline(Quaternion q1, Quaternion outTangent1, Quaternion q2, Quaternion inTangent2, float t) -{ - float t2 = t*t; - float t3 = t2*t; - float h00 = 2*t3 - 3*t2 + 1; - float h10 = t3 - 2*t2 + t; - float h01 = -2*t3 + 3*t2; - float h11 = t3 - t2; - - Quaternion p0 = QuaternionScale(q1, h00); - Quaternion m0 = QuaternionScale(outTangent1, h10); - Quaternion p1 = QuaternionScale(q2, h01); - Quaternion m1 = QuaternionScale(inTangent2, h11); - - Quaternion result = { 0 }; - - result = QuaternionAdd(p0, m0); - result = QuaternionAdd(result, p1); - result = QuaternionAdd(result, m1); - result = QuaternionNormalize(result); - - return result; -} - -// Calculate quaternion based on the rotation from one vector to another -RMAPI Quaternion QuaternionFromVector3ToVector3(Vector3 from, Vector3 to) -{ - Quaternion result = { 0 }; - - float cos2Theta = (from.x*to.x + from.y*to.y + from.z*to.z); // Vector3DotProduct(from, to) - Vector3 cross = { from.y*to.z - from.z*to.y, from.z*to.x - from.x*to.z, from.x*to.y - from.y*to.x }; // Vector3CrossProduct(from, to) - - result.x = cross.x; - result.y = cross.y; - result.z = cross.z; - result.w = 1.0f + cos2Theta; - - // QuaternionNormalize(q); - // NOTE: Normalize to essentially nlerp the original and identity to 0.5 - Quaternion q = result; - float length = sqrtf(q.x*q.x + q.y*q.y + q.z*q.z + q.w*q.w); - if (length == 0.0f) length = 1.0f; - float ilength = 1.0f/length; - - result.x = q.x*ilength; - result.y = q.y*ilength; - result.z = q.z*ilength; - result.w = q.w*ilength; - - return result; -} - -// Get a quaternion for a given rotation matrix -RMAPI Quaternion QuaternionFromMatrix(Matrix mat) -{ - Quaternion result = { 0 }; - - float fourWSquaredMinus1 = mat.m0 + mat.m5 + mat.m10; - float fourXSquaredMinus1 = mat.m0 - mat.m5 - mat.m10; - float fourYSquaredMinus1 = mat.m5 - mat.m0 - mat.m10; - float fourZSquaredMinus1 = mat.m10 - mat.m0 - mat.m5; - - int biggestIndex = 0; - float fourBiggestSquaredMinus1 = fourWSquaredMinus1; - if (fourXSquaredMinus1 > fourBiggestSquaredMinus1) - { - fourBiggestSquaredMinus1 = fourXSquaredMinus1; - biggestIndex = 1; - } - - if (fourYSquaredMinus1 > fourBiggestSquaredMinus1) - { - fourBiggestSquaredMinus1 = fourYSquaredMinus1; - biggestIndex = 2; - } - - if (fourZSquaredMinus1 > fourBiggestSquaredMinus1) - { - fourBiggestSquaredMinus1 = fourZSquaredMinus1; - biggestIndex = 3; - } - - float biggestVal = sqrtf(fourBiggestSquaredMinus1 + 1.0f)*0.5f; - float mult = 0.25f/biggestVal; - - switch (biggestIndex) - { - case 0: - result.w = biggestVal; - result.x = (mat.m6 - mat.m9)*mult; - result.y = (mat.m8 - mat.m2)*mult; - result.z = (mat.m1 - mat.m4)*mult; - break; - case 1: - result.x = biggestVal; - result.w = (mat.m6 - mat.m9)*mult; - result.y = (mat.m1 + mat.m4)*mult; - result.z = (mat.m8 + mat.m2)*mult; - break; - case 2: - result.y = biggestVal; - result.w = (mat.m8 - mat.m2)*mult; - result.x = (mat.m1 + mat.m4)*mult; - result.z = (mat.m6 + mat.m9)*mult; - break; - case 3: - result.z = biggestVal; - result.w = (mat.m1 - mat.m4)*mult; - result.x = (mat.m8 + mat.m2)*mult; - result.y = (mat.m6 + mat.m9)*mult; - break; - } - - return result; -} - -// Get a matrix for a given quaternion -RMAPI Matrix QuaternionToMatrix(Quaternion q) -{ - Matrix result = { 1.0f, 0.0f, 0.0f, 0.0f, - 0.0f, 1.0f, 0.0f, 0.0f, - 0.0f, 0.0f, 1.0f, 0.0f, - 0.0f, 0.0f, 0.0f, 1.0f }; // MatrixIdentity() - - float a2 = q.x*q.x; - float b2 = q.y*q.y; - float c2 = q.z*q.z; - float ac = q.x*q.z; - float ab = q.x*q.y; - float bc = q.y*q.z; - float ad = q.w*q.x; - float bd = q.w*q.y; - float cd = q.w*q.z; - - result.m0 = 1 - 2*(b2 + c2); - result.m1 = 2*(ab + cd); - result.m2 = 2*(ac - bd); - - result.m4 = 2*(ab - cd); - result.m5 = 1 - 2*(a2 + c2); - result.m6 = 2*(bc + ad); - - result.m8 = 2*(ac + bd); - result.m9 = 2*(bc - ad); - result.m10 = 1 - 2*(a2 + b2); - - return result; -} - -// Get rotation quaternion for an angle and axis -// NOTE: Angle must be provided in radians -RMAPI Quaternion QuaternionFromAxisAngle(Vector3 axis, float angle) -{ - Quaternion result = { 0.0f, 0.0f, 0.0f, 1.0f }; - - float axisLength = sqrtf(axis.x*axis.x + axis.y*axis.y + axis.z*axis.z); - - if (axisLength != 0.0f) - { - angle *= 0.5f; - - float length = 0.0f; - float ilength = 0.0f; - - // Vector3Normalize(axis) - length = axisLength; - if (length == 0.0f) length = 1.0f; - ilength = 1.0f/length; - axis.x *= ilength; - axis.y *= ilength; - axis.z *= ilength; - - float sinres = sinf(angle); - float cosres = cosf(angle); - - result.x = axis.x*sinres; - result.y = axis.y*sinres; - result.z = axis.z*sinres; - result.w = cosres; - - // QuaternionNormalize(q); - Quaternion q = result; - length = sqrtf(q.x*q.x + q.y*q.y + q.z*q.z + q.w*q.w); - if (length == 0.0f) length = 1.0f; - ilength = 1.0f/length; - result.x = q.x*ilength; - result.y = q.y*ilength; - result.z = q.z*ilength; - result.w = q.w*ilength; - } - - return result; -} - -// Get the rotation angle and axis for a given quaternion -RMAPI void QuaternionToAxisAngle(Quaternion q, Vector3 *outAxis, float *outAngle) -{ - if (fabsf(q.w) > 1.0f) - { - // QuaternionNormalize(q); - float length = sqrtf(q.x*q.x + q.y*q.y + q.z*q.z + q.w*q.w); - if (length == 0.0f) length = 1.0f; - float ilength = 1.0f/length; - - q.x = q.x*ilength; - q.y = q.y*ilength; - q.z = q.z*ilength; - q.w = q.w*ilength; - } - - Vector3 resAxis = { 0.0f, 0.0f, 0.0f }; - float resAngle = 2.0f*acosf(q.w); - float den = sqrtf(1.0f - q.w*q.w); - - if (den > EPSILON) - { - resAxis.x = q.x/den; - resAxis.y = q.y/den; - resAxis.z = q.z/den; - } - else - { - // This occurs when the angle is zero. - // Not a problem: just set an arbitrary normalized axis. - resAxis.x = 1.0f; - } - - *outAxis = resAxis; - *outAngle = resAngle; -} - -// Get the quaternion equivalent to Euler angles -// NOTE: Rotation order is ZYX -RMAPI Quaternion QuaternionFromEuler(float pitch, float yaw, float roll) -{ - Quaternion result = { 0 }; - - float x0 = cosf(pitch*0.5f); - float x1 = sinf(pitch*0.5f); - float y0 = cosf(yaw*0.5f); - float y1 = sinf(yaw*0.5f); - float z0 = cosf(roll*0.5f); - float z1 = sinf(roll*0.5f); - - result.x = x1*y0*z0 - x0*y1*z1; - result.y = x0*y1*z0 + x1*y0*z1; - result.z = x0*y0*z1 - x1*y1*z0; - result.w = x0*y0*z0 + x1*y1*z1; - - return result; -} - -// Get the Euler angles equivalent to quaternion (roll, pitch, yaw) -// NOTE: Angles are returned in a Vector3 struct in radians -RMAPI Vector3 QuaternionToEuler(Quaternion q) -{ - Vector3 result = { 0 }; - - // Roll (x-axis rotation) - float x0 = 2.0f*(q.w*q.x + q.y*q.z); - float x1 = 1.0f - 2.0f*(q.x*q.x + q.y*q.y); - result.x = atan2f(x0, x1); - - // Pitch (y-axis rotation) - float y0 = 2.0f*(q.w*q.y - q.z*q.x); - y0 = y0 > 1.0f ? 1.0f : y0; - y0 = y0 < -1.0f ? -1.0f : y0; - result.y = asinf(y0); - - // Yaw (z-axis rotation) - float z0 = 2.0f*(q.w*q.z + q.x*q.y); - float z1 = 1.0f - 2.0f*(q.y*q.y + q.z*q.z); - result.z = atan2f(z0, z1); - - return result; -} - -// Transform a quaternion given a transformation matrix -RMAPI Quaternion QuaternionTransform(Quaternion q, Matrix mat) -{ - Quaternion result = { 0 }; - - result.x = mat.m0*q.x + mat.m4*q.y + mat.m8*q.z + mat.m12*q.w; - result.y = mat.m1*q.x + mat.m5*q.y + mat.m9*q.z + mat.m13*q.w; - result.z = mat.m2*q.x + mat.m6*q.y + mat.m10*q.z + mat.m14*q.w; - result.w = mat.m3*q.x + mat.m7*q.y + mat.m11*q.z + mat.m15*q.w; - - return result; -} - -// Check whether two given quaternions are almost equal -RMAPI int QuaternionEquals(Quaternion p, Quaternion q) -{ -#if !defined(EPSILON) - #define EPSILON 0.000001f -#endif - - int result = (((fabsf(p.x - q.x)) <= (EPSILON*fmaxf(1.0f, fmaxf(fabsf(p.x), fabsf(q.x))))) && - ((fabsf(p.y - q.y)) <= (EPSILON*fmaxf(1.0f, fmaxf(fabsf(p.y), fabsf(q.y))))) && - ((fabsf(p.z - q.z)) <= (EPSILON*fmaxf(1.0f, fmaxf(fabsf(p.z), fabsf(q.z))))) && - ((fabsf(p.w - q.w)) <= (EPSILON*fmaxf(1.0f, fmaxf(fabsf(p.w), fabsf(q.w)))))) || - (((fabsf(p.x + q.x)) <= (EPSILON*fmaxf(1.0f, fmaxf(fabsf(p.x), fabsf(q.x))))) && - ((fabsf(p.y + q.y)) <= (EPSILON*fmaxf(1.0f, fmaxf(fabsf(p.y), fabsf(q.y))))) && - ((fabsf(p.z + q.z)) <= (EPSILON*fmaxf(1.0f, fmaxf(fabsf(p.z), fabsf(q.z))))) && - ((fabsf(p.w + q.w)) <= (EPSILON*fmaxf(1.0f, fmaxf(fabsf(p.w), fabsf(q.w)))))); - - return result; -} - -// Decompose a transformation matrix into its rotational, translational and scaling components -RMAPI void MatrixDecompose(Matrix mat, Vector3 *translation, Quaternion *rotation, Vector3 *scale) -{ - // Extract translation. - translation->x = mat.m12; - translation->y = mat.m13; - translation->z = mat.m14; - - // Extract upper-left for determinant computation - const float a = mat.m0; - const float b = mat.m4; - const float c = mat.m8; - const float d = mat.m1; - const float e = mat.m5; - const float f = mat.m9; - const float g = mat.m2; - const float h = mat.m6; - const float i = mat.m10; - const float A = e*i - f*h; - const float B = f*g - d*i; - const float C = d*h - e*g; - - // Extract scale - const float det = a*A + b*B + c*C; - Vector3 abc = { a, b, c }; - Vector3 def = { d, e, f }; - Vector3 ghi = { g, h, i }; - - float scalex = Vector3Length(abc); - float scaley = Vector3Length(def); - float scalez = Vector3Length(ghi); - Vector3 s = { scalex, scaley, scalez }; - - if (det < 0) s = Vector3Negate(s); - - *scale = s; - - // Remove scale from the matrix if it is not close to zero - Matrix clone = mat; - if (!FloatEquals(det, 0)) - { - clone.m0 /= s.x; - clone.m4 /= s.x; - clone.m8 /= s.x; - clone.m1 /= s.y; - clone.m5 /= s.y; - clone.m9 /= s.y; - clone.m2 /= s.z; - clone.m6 /= s.z; - clone.m10 /= s.z; - - // Extract rotation - *rotation = QuaternionFromMatrix(clone); - } - else - { - // Set to identity if close to zero - *rotation = QuaternionIdentity(); - } -} - -#if defined(__cplusplus) && !defined(RAYMATH_DISABLE_CPP_OPERATORS) - -// Optional C++ math operators -//------------------------------------------------------------------------------- - -// Vector2 operators -static constexpr Vector2 Vector2Zeros = { 0, 0 }; -static constexpr Vector2 Vector2Ones = { 1, 1 }; -static constexpr Vector2 Vector2UnitX = { 1, 0 }; -static constexpr Vector2 Vector2UnitY = { 0, 1 }; - -inline Vector2 operator + (const Vector2& lhs, const Vector2& rhs) -{ - return Vector2Add(lhs, rhs); -} - -inline const Vector2& operator += (Vector2& lhs, const Vector2& rhs) -{ - lhs = Vector2Add(lhs, rhs); - return lhs; -} - -inline Vector2 operator - (const Vector2& lhs, const Vector2& rhs) -{ - return Vector2Subtract(lhs, rhs); -} - -inline const Vector2& operator -= (Vector2& lhs, const Vector2& rhs) -{ - lhs = Vector2Subtract(lhs, rhs); - return lhs; -} - -inline Vector2 operator * (const Vector2& lhs, const float& rhs) -{ - return Vector2Scale(lhs, rhs); -} - -inline const Vector2& operator *= (Vector2& lhs, const float& rhs) -{ - lhs = Vector2Scale(lhs, rhs); - return lhs; -} - -inline Vector2 operator * (const Vector2& lhs, const Vector2& rhs) -{ - return Vector2Multiply(lhs, rhs); -} - -inline const Vector2& operator *= (Vector2& lhs, const Vector2& rhs) -{ - lhs = Vector2Multiply(lhs, rhs); - return lhs; -} - -inline Vector2 operator * (const Vector2& lhs, const Matrix& rhs) -{ - return Vector2Transform(lhs, rhs); -} - -inline const Vector2& operator *= (Vector2& lhs, const Matrix& rhs) -{ - lhs = Vector2Transform(lhs, rhs); - return lhs; -} - -inline Vector2 operator / (const Vector2& lhs, const float& rhs) -{ - return Vector2Scale(lhs, 1.0f / rhs); -} - -inline const Vector2& operator /= (Vector2& lhs, const float& rhs) -{ - lhs = Vector2Scale(lhs, 1.0f / rhs); - return lhs; -} - -inline Vector2 operator / (const Vector2& lhs, const Vector2& rhs) -{ - return Vector2Divide(lhs, rhs); -} - -inline const Vector2& operator /= (Vector2& lhs, const Vector2& rhs) -{ - lhs = Vector2Divide(lhs, rhs); - return lhs; -} - -inline bool operator == (const Vector2& lhs, const Vector2& rhs) -{ - return FloatEquals(lhs.x, rhs.x) && FloatEquals(lhs.y, rhs.y); -} - -inline bool operator != (const Vector2& lhs, const Vector2& rhs) -{ - return !FloatEquals(lhs.x, rhs.x) || !FloatEquals(lhs.y, rhs.y); -} - -// Vector3 operators -static constexpr Vector3 Vector3Zeros = { 0, 0, 0 }; -static constexpr Vector3 Vector3Ones = { 1, 1, 1 }; -static constexpr Vector3 Vector3UnitX = { 1, 0, 0 }; -static constexpr Vector3 Vector3UnitY = { 0, 1, 0 }; -static constexpr Vector3 Vector3UnitZ = { 0, 0, 1 }; - -inline Vector3 operator + (const Vector3& lhs, const Vector3& rhs) -{ - return Vector3Add(lhs, rhs); -} - -inline const Vector3& operator += (Vector3& lhs, const Vector3& rhs) -{ - lhs = Vector3Add(lhs, rhs); - return lhs; -} - -inline Vector3 operator - (const Vector3& lhs, const Vector3& rhs) -{ - return Vector3Subtract(lhs, rhs); -} - -inline const Vector3& operator -= (Vector3& lhs, const Vector3& rhs) -{ - lhs = Vector3Subtract(lhs, rhs); - return lhs; -} - -inline Vector3 operator * (const Vector3& lhs, const float& rhs) -{ - return Vector3Scale(lhs, rhs); -} - -inline const Vector3& operator *= (Vector3& lhs, const float& rhs) -{ - lhs = Vector3Scale(lhs, rhs); - return lhs; -} - -inline Vector3 operator * (const Vector3& lhs, const Vector3& rhs) -{ - return Vector3Multiply(lhs, rhs); -} - -inline const Vector3& operator *= (Vector3& lhs, const Vector3& rhs) -{ - lhs = Vector3Multiply(lhs, rhs); - return lhs; -} - -inline Vector3 operator * (const Vector3& lhs, const Matrix& rhs) -{ - return Vector3Transform(lhs, rhs); -} - -inline const Vector3& operator *= (Vector3& lhs, const Matrix& rhs) -{ - lhs = Vector3Transform(lhs, rhs); - return lhs; -} - -inline Vector3 operator / (const Vector3& lhs, const float& rhs) -{ - return Vector3Scale(lhs, 1.0f / rhs); -} - -inline const Vector3& operator /= (Vector3& lhs, const float& rhs) -{ - lhs = Vector3Scale(lhs, 1.0f / rhs); - return lhs; -} - -inline Vector3 operator / (const Vector3& lhs, const Vector3& rhs) -{ - return Vector3Divide(lhs, rhs); -} - -inline const Vector3& operator /= (Vector3& lhs, const Vector3& rhs) -{ - lhs = Vector3Divide(lhs, rhs); - return lhs; -} - -inline bool operator == (const Vector3& lhs, const Vector3& rhs) -{ - return FloatEquals(lhs.x, rhs.x) && FloatEquals(lhs.y, rhs.y) && FloatEquals(lhs.z, rhs.z); -} - -inline bool operator != (const Vector3& lhs, const Vector3& rhs) -{ - return !FloatEquals(lhs.x, rhs.x) || !FloatEquals(lhs.y, rhs.y) || !FloatEquals(lhs.z, rhs.z); -} - -// Vector4 operators -static constexpr Vector4 Vector4Zeros = { 0, 0, 0, 0 }; -static constexpr Vector4 Vector4Ones = { 1, 1, 1, 1 }; -static constexpr Vector4 Vector4UnitX = { 1, 0, 0, 0 }; -static constexpr Vector4 Vector4UnitY = { 0, 1, 0, 0 }; -static constexpr Vector4 Vector4UnitZ = { 0, 0, 1, 0 }; -static constexpr Vector4 Vector4UnitW = { 0, 0, 0, 1 }; - -inline Vector4 operator + (const Vector4& lhs, const Vector4& rhs) -{ - return Vector4Add(lhs, rhs); -} - -inline const Vector4& operator += (Vector4& lhs, const Vector4& rhs) -{ - lhs = Vector4Add(lhs, rhs); - return lhs; -} - -inline Vector4 operator - (const Vector4& lhs, const Vector4& rhs) -{ - return Vector4Subtract(lhs, rhs); -} - -inline const Vector4& operator -= (Vector4& lhs, const Vector4& rhs) -{ - lhs = Vector4Subtract(lhs, rhs); - return lhs; -} - -inline Vector4 operator * (const Vector4& lhs, const float& rhs) -{ - return Vector4Scale(lhs, rhs); -} - -inline const Vector4& operator *= (Vector4& lhs, const float& rhs) -{ - lhs = Vector4Scale(lhs, rhs); - return lhs; -} - -inline Vector4 operator * (const Vector4& lhs, const Vector4& rhs) -{ - return Vector4Multiply(lhs, rhs); -} - -inline const Vector4& operator *= (Vector4& lhs, const Vector4& rhs) -{ - lhs = Vector4Multiply(lhs, rhs); - return lhs; -} - -inline Vector4 operator / (const Vector4& lhs, const float& rhs) -{ - return Vector4Scale(lhs, 1.0f / rhs); -} - -inline const Vector4& operator /= (Vector4& lhs, const float& rhs) -{ - lhs = Vector4Scale(lhs, 1.0f / rhs); - return lhs; -} - -inline Vector4 operator / (const Vector4& lhs, const Vector4& rhs) -{ - return Vector4Divide(lhs, rhs); -} - -inline const Vector4& operator /= (Vector4& lhs, const Vector4& rhs) -{ - lhs = Vector4Divide(lhs, rhs); - return lhs; -} - -inline bool operator == (const Vector4& lhs, const Vector4& rhs) -{ - return FloatEquals(lhs.x, rhs.x) && FloatEquals(lhs.y, rhs.y) && FloatEquals(lhs.z, rhs.z) && FloatEquals(lhs.w, rhs.w); -} - -inline bool operator != (const Vector4& lhs, const Vector4& rhs) -{ - return !FloatEquals(lhs.x, rhs.x) || !FloatEquals(lhs.y, rhs.y) || !FloatEquals(lhs.z, rhs.z) || !FloatEquals(lhs.w, rhs.w); -} - -// Quaternion operators -static constexpr Quaternion QuaternionZeros = { 0, 0, 0, 0 }; -static constexpr Quaternion QuaternionOnes = { 1, 1, 1, 1 }; -static constexpr Quaternion QuaternionUnitX = { 0, 0, 0, 1 }; - -inline Quaternion operator + (const Quaternion& lhs, const float& rhs) -{ - return QuaternionAddValue(lhs, rhs); -} - -inline const Quaternion& operator += (Quaternion& lhs, const float& rhs) -{ - lhs = QuaternionAddValue(lhs, rhs); - return lhs; -} - -inline Quaternion operator - (const Quaternion& lhs, const float& rhs) -{ - return QuaternionSubtractValue(lhs, rhs); -} - -inline const Quaternion& operator -= (Quaternion& lhs, const float& rhs) -{ - lhs = QuaternionSubtractValue(lhs, rhs); - return lhs; -} - -inline Quaternion operator * (const Quaternion& lhs, const Matrix& rhs) -{ - return QuaternionTransform(lhs, rhs); -} - -inline const Quaternion& operator *= (Quaternion& lhs, const Matrix& rhs) -{ - lhs = QuaternionTransform(lhs, rhs); - return lhs; -} - -// Matrix operators -inline Matrix operator + (const Matrix& lhs, const Matrix& rhs) -{ - return MatrixAdd(lhs, rhs); -} - -inline const Matrix& operator += (Matrix& lhs, const Matrix& rhs) -{ - lhs = MatrixAdd(lhs, rhs); - return lhs; -} - -inline Matrix operator - (const Matrix& lhs, const Matrix& rhs) -{ - return MatrixSubtract(lhs, rhs); -} - -inline const Matrix& operator -= (Matrix& lhs, const Matrix& rhs) -{ - lhs = MatrixSubtract(lhs, rhs); - return lhs; -} - -inline Matrix operator * (const Matrix& lhs, const Matrix& rhs) -{ - return MatrixMultiply(lhs, rhs); -} - -inline const Matrix& operator *= (Matrix& lhs, const Matrix& rhs) -{ - lhs = MatrixMultiply(lhs, rhs); - return lhs; -} -//------------------------------------------------------------------------------- -#endif // C++ operators - -#endif // RAYMATH_H diff --git a/third_party/raylib/include/rlgl.h b/third_party/raylib/include/rlgl.h deleted file mode 100644 index 92971df627..0000000000 --- a/third_party/raylib/include/rlgl.h +++ /dev/null @@ -1,5262 +0,0 @@ -/********************************************************************************************** -* -* rlgl v5.0 - A multi-OpenGL abstraction layer with an immediate-mode style API -* -* DESCRIPTION: -* An abstraction layer for multiple OpenGL versions (1.1, 2.1, 3.3 Core, 4.3 Core, ES 2.0, ES 3.0) -* that provides a pseudo-OpenGL 1.1 immediate-mode style API (rlVertex, rlTranslate, rlRotate...) -* -* ADDITIONAL NOTES: -* When choosing an OpenGL backend different than OpenGL 1.1, some internal buffer are -* initialized on rlglInit() to accumulate vertex data -* -* When an internal state change is required all the stored vertex data is renderer in batch, -* additionally, rlDrawRenderBatchActive() could be called to force flushing of the batch -* -* Some resources are also loaded for convenience, here the complete list: -* - Default batch (RLGL.defaultBatch): RenderBatch system to accumulate vertex data -* - Default texture (RLGL.defaultTextureId): 1x1 white pixel R8G8B8A8 -* - Default shader (RLGL.State.defaultShaderId, RLGL.State.defaultShaderLocs) -* -* Internal buffer (and resources) must be manually unloaded calling rlglClose() -* -* CONFIGURATION: -* #define GRAPHICS_API_OPENGL_11 -* #define GRAPHICS_API_OPENGL_21 -* #define GRAPHICS_API_OPENGL_33 -* #define GRAPHICS_API_OPENGL_43 -* #define GRAPHICS_API_OPENGL_ES2 -* #define GRAPHICS_API_OPENGL_ES3 -* Use selected OpenGL graphics backend, should be supported by platform -* Those preprocessor defines are only used on rlgl module, if OpenGL version is -* required by any other module, use rlGetVersion() to check it -* -* #define RLGL_IMPLEMENTATION -* Generates the implementation of the library into the included file -* If not defined, the library is in header only mode and can be included in other headers -* or source files without problems. But only ONE file should hold the implementation -* -* #define RLGL_RENDER_TEXTURES_HINT -* Enable framebuffer objects (fbo) support (enabled by default) -* Some GPUs could not support them despite the OpenGL version -* -* #define RLGL_SHOW_GL_DETAILS_INFO -* Show OpenGL extensions and capabilities detailed logs on init -* -* #define RLGL_ENABLE_OPENGL_DEBUG_CONTEXT -* Enable debug context (only available on OpenGL 4.3) -* -* rlgl capabilities could be customized just defining some internal -* values before library inclusion (default values listed): -* -* #define RL_DEFAULT_BATCH_BUFFER_ELEMENTS 8192 // Default internal render batch elements limits -* #define RL_DEFAULT_BATCH_BUFFERS 1 // Default number of batch buffers (multi-buffering) -* #define RL_DEFAULT_BATCH_DRAWCALLS 256 // Default number of batch draw calls (by state changes: mode, texture) -* #define RL_DEFAULT_BATCH_MAX_TEXTURE_UNITS 4 // Maximum number of textures units that can be activated on batch drawing (SetShaderValueTexture()) -* -* #define RL_MAX_MATRIX_STACK_SIZE 32 // Maximum size of internal Matrix stack -* #define RL_MAX_SHADER_LOCATIONS 32 // Maximum number of shader locations supported -* #define RL_CULL_DISTANCE_NEAR 0.01 // Default projection matrix near cull distance -* #define RL_CULL_DISTANCE_FAR 1000.0 // Default projection matrix far cull distance -* -* When loading a shader, the following vertex attributes and uniform -* location names are tried to be set automatically: -* -* #define RL_DEFAULT_SHADER_ATTRIB_NAME_POSITION "vertexPosition" // Bound by default to shader location: RL_DEFAULT_SHADER_ATTRIB_LOCATION_POSITION -* #define RL_DEFAULT_SHADER_ATTRIB_NAME_TEXCOORD "vertexTexCoord" // Bound by default to shader location: RL_DEFAULT_SHADER_ATTRIB_LOCATION_TEXCOORD -* #define RL_DEFAULT_SHADER_ATTRIB_NAME_NORMAL "vertexNormal" // Bound by default to shader location: RL_DEFAULT_SHADER_ATTRIB_LOCATION_NORMAL -* #define RL_DEFAULT_SHADER_ATTRIB_NAME_COLOR "vertexColor" // Bound by default to shader location: RL_DEFAULT_SHADER_ATTRIB_LOCATION_COLOR -* #define RL_DEFAULT_SHADER_ATTRIB_NAME_TANGENT "vertexTangent" // Bound by default to shader location: RL_DEFAULT_SHADER_ATTRIB_LOCATION_TANGENT -* #define RL_DEFAULT_SHADER_ATTRIB_NAME_TEXCOORD2 "vertexTexCoord2" // Bound by default to shader location: RL_DEFAULT_SHADER_ATTRIB_LOCATION_TEXCOORD2 -* #define RL_DEFAULT_SHADER_ATTRIB_NAME_BONEIDS "vertexBoneIds" // Bound by default to shader location: RL_DEFAULT_SHADER_ATTRIB_LOCATION_BONEIDS -* #define RL_DEFAULT_SHADER_ATTRIB_NAME_BONEWEIGHTS "vertexBoneWeights" // Bound by default to shader location: RL_DEFAULT_SHADER_ATTRIB_LOCATION_BONEWEIGHTS -* #define RL_DEFAULT_SHADER_UNIFORM_NAME_MVP "mvp" // model-view-projection matrix -* #define RL_DEFAULT_SHADER_UNIFORM_NAME_VIEW "matView" // view matrix -* #define RL_DEFAULT_SHADER_UNIFORM_NAME_PROJECTION "matProjection" // projection matrix -* #define RL_DEFAULT_SHADER_UNIFORM_NAME_MODEL "matModel" // model matrix -* #define RL_DEFAULT_SHADER_UNIFORM_NAME_NORMAL "matNormal" // normal matrix (transpose(inverse(matModelView))) -* #define RL_DEFAULT_SHADER_UNIFORM_NAME_COLOR "colDiffuse" // color diffuse (base tint color, multiplied by texture color) -* #define RL_DEFAULT_SHADER_UNIFORM_NAME_BONE_MATRICES "boneMatrices" // bone matrices -* #define RL_DEFAULT_SHADER_SAMPLER2D_NAME_TEXTURE0 "texture0" // texture0 (texture slot active 0) -* #define RL_DEFAULT_SHADER_SAMPLER2D_NAME_TEXTURE1 "texture1" // texture1 (texture slot active 1) -* #define RL_DEFAULT_SHADER_SAMPLER2D_NAME_TEXTURE2 "texture2" // texture2 (texture slot active 2) -* -* DEPENDENCIES: -* - OpenGL libraries (depending on platform and OpenGL version selected) -* - GLAD OpenGL extensions loading library (only for OpenGL 3.3 Core, 4.3 Core) -* -* -* LICENSE: zlib/libpng -* -* Copyright (c) 2014-2024 Ramon Santamaria (@raysan5) -* -* This software is provided "as-is", without any express or implied warranty. In no event -* will the authors be held liable for any damages arising from the use of this software. -* -* Permission is granted to anyone to use this software for any purpose, including commercial -* applications, and to alter it and redistribute it freely, subject to the following restrictions: -* -* 1. The origin of this software must not be misrepresented; you must not claim that you -* wrote the original software. If you use this software in a product, an acknowledgment -* in the product documentation would be appreciated but is not required. -* -* 2. Altered source versions must be plainly marked as such, and must not be misrepresented -* as being the original software. -* -* 3. This notice may not be removed or altered from any source distribution. -* -**********************************************************************************************/ - -#ifndef RLGL_H -#define RLGL_H - -#define RLGL_VERSION "5.0" - -// Function specifiers in case library is build/used as a shared library -// NOTE: Microsoft specifiers to tell compiler that symbols are imported/exported from a .dll -// NOTE: visibility(default) attribute makes symbols "visible" when compiled with -fvisibility=hidden -#if defined(_WIN32) && defined(BUILD_LIBTYPE_SHARED) - #define RLAPI __declspec(dllexport) // We are building the library as a Win32 shared library (.dll) -#elif defined(BUILD_LIBTYPE_SHARED) - #define RLAPI __attribute__((visibility("default"))) // We are building the library as a Unix shared library (.so/.dylib) -#elif defined(_WIN32) && defined(USE_LIBTYPE_SHARED) - #define RLAPI __declspec(dllimport) // We are using the library as a Win32 shared library (.dll) -#endif - -// Function specifiers definition -#ifndef RLAPI - #define RLAPI // Functions defined as 'extern' by default (implicit specifiers) -#endif - -// Support TRACELOG macros -#ifndef TRACELOG - #define TRACELOG(level, ...) (void)0 - #define TRACELOGD(...) (void)0 -#endif - -// Allow custom memory allocators -#ifndef RL_MALLOC - #define RL_MALLOC(sz) malloc(sz) -#endif -#ifndef RL_CALLOC - #define RL_CALLOC(n,sz) calloc(n,sz) -#endif -#ifndef RL_REALLOC - #define RL_REALLOC(n,sz) realloc(n,sz) -#endif -#ifndef RL_FREE - #define RL_FREE(p) free(p) -#endif - -// Security check in case no GRAPHICS_API_OPENGL_* defined -#if !defined(GRAPHICS_API_OPENGL_11) && \ - !defined(GRAPHICS_API_OPENGL_21) && \ - !defined(GRAPHICS_API_OPENGL_33) && \ - !defined(GRAPHICS_API_OPENGL_43) && \ - !defined(GRAPHICS_API_OPENGL_ES2) && \ - !defined(GRAPHICS_API_OPENGL_ES3) - #define GRAPHICS_API_OPENGL_33 -#endif - -// Security check in case multiple GRAPHICS_API_OPENGL_* defined -#if defined(GRAPHICS_API_OPENGL_11) - #if defined(GRAPHICS_API_OPENGL_21) - #undef GRAPHICS_API_OPENGL_21 - #endif - #if defined(GRAPHICS_API_OPENGL_33) - #undef GRAPHICS_API_OPENGL_33 - #endif - #if defined(GRAPHICS_API_OPENGL_43) - #undef GRAPHICS_API_OPENGL_43 - #endif - #if defined(GRAPHICS_API_OPENGL_ES2) - #undef GRAPHICS_API_OPENGL_ES2 - #endif -#endif - -// OpenGL 2.1 uses most of OpenGL 3.3 Core functionality -// WARNING: Specific parts are checked with #if defines -#if defined(GRAPHICS_API_OPENGL_21) - #define GRAPHICS_API_OPENGL_33 -#endif - -// OpenGL 4.3 uses OpenGL 3.3 Core functionality -#if defined(GRAPHICS_API_OPENGL_43) - #define GRAPHICS_API_OPENGL_33 -#endif - -// OpenGL ES 3.0 uses OpenGL ES 2.0 functionality (and more) -#if defined(GRAPHICS_API_OPENGL_ES3) - #define GRAPHICS_API_OPENGL_ES2 -#endif - -// Support framebuffer objects by default -// NOTE: Some driver implementation do not support it, despite they should -#define RLGL_RENDER_TEXTURES_HINT - -//---------------------------------------------------------------------------------- -// Defines and Macros -//---------------------------------------------------------------------------------- - -// Default internal render batch elements limits -#ifndef RL_DEFAULT_BATCH_BUFFER_ELEMENTS - #if defined(GRAPHICS_API_OPENGL_11) || defined(GRAPHICS_API_OPENGL_33) - // This is the maximum amount of elements (quads) per batch - // NOTE: Be careful with text, every letter maps to a quad - #define RL_DEFAULT_BATCH_BUFFER_ELEMENTS 8192 - #endif - #if defined(GRAPHICS_API_OPENGL_ES2) - // We reduce memory sizes for embedded systems (RPI and HTML5) - // NOTE: On HTML5 (emscripten) this is allocated on heap, - // by default it's only 16MB!...just take care... - #define RL_DEFAULT_BATCH_BUFFER_ELEMENTS 2048 - #endif -#endif -#ifndef RL_DEFAULT_BATCH_BUFFERS - #define RL_DEFAULT_BATCH_BUFFERS 1 // Default number of batch buffers (multi-buffering) -#endif -#ifndef RL_DEFAULT_BATCH_DRAWCALLS - #define RL_DEFAULT_BATCH_DRAWCALLS 256 // Default number of batch draw calls (by state changes: mode, texture) -#endif -#ifndef RL_DEFAULT_BATCH_MAX_TEXTURE_UNITS - #define RL_DEFAULT_BATCH_MAX_TEXTURE_UNITS 4 // Maximum number of textures units that can be activated on batch drawing (SetShaderValueTexture()) -#endif - -// Internal Matrix stack -#ifndef RL_MAX_MATRIX_STACK_SIZE - #define RL_MAX_MATRIX_STACK_SIZE 32 // Maximum size of Matrix stack -#endif - -// Shader limits -#ifndef RL_MAX_SHADER_LOCATIONS - #define RL_MAX_SHADER_LOCATIONS 32 // Maximum number of shader locations supported -#endif - -// Projection matrix culling -#ifndef RL_CULL_DISTANCE_NEAR - #define RL_CULL_DISTANCE_NEAR 0.01 // Default near cull distance -#endif -#ifndef RL_CULL_DISTANCE_FAR - #define RL_CULL_DISTANCE_FAR 1000.0 // Default far cull distance -#endif - -// Texture parameters (equivalent to OpenGL defines) -#define RL_TEXTURE_WRAP_S 0x2802 // GL_TEXTURE_WRAP_S -#define RL_TEXTURE_WRAP_T 0x2803 // GL_TEXTURE_WRAP_T -#define RL_TEXTURE_MAG_FILTER 0x2800 // GL_TEXTURE_MAG_FILTER -#define RL_TEXTURE_MIN_FILTER 0x2801 // GL_TEXTURE_MIN_FILTER - -#define RL_TEXTURE_FILTER_NEAREST 0x2600 // GL_NEAREST -#define RL_TEXTURE_FILTER_LINEAR 0x2601 // GL_LINEAR -#define RL_TEXTURE_FILTER_MIP_NEAREST 0x2700 // GL_NEAREST_MIPMAP_NEAREST -#define RL_TEXTURE_FILTER_NEAREST_MIP_LINEAR 0x2702 // GL_NEAREST_MIPMAP_LINEAR -#define RL_TEXTURE_FILTER_LINEAR_MIP_NEAREST 0x2701 // GL_LINEAR_MIPMAP_NEAREST -#define RL_TEXTURE_FILTER_MIP_LINEAR 0x2703 // GL_LINEAR_MIPMAP_LINEAR -#define RL_TEXTURE_FILTER_ANISOTROPIC 0x3000 // Anisotropic filter (custom identifier) -#define RL_TEXTURE_MIPMAP_BIAS_RATIO 0x4000 // Texture mipmap bias, percentage ratio (custom identifier) - -#define RL_TEXTURE_WRAP_REPEAT 0x2901 // GL_REPEAT -#define RL_TEXTURE_WRAP_CLAMP 0x812F // GL_CLAMP_TO_EDGE -#define RL_TEXTURE_WRAP_MIRROR_REPEAT 0x8370 // GL_MIRRORED_REPEAT -#define RL_TEXTURE_WRAP_MIRROR_CLAMP 0x8742 // GL_MIRROR_CLAMP_EXT - -// Matrix modes (equivalent to OpenGL) -#define RL_MODELVIEW 0x1700 // GL_MODELVIEW -#define RL_PROJECTION 0x1701 // GL_PROJECTION -#define RL_TEXTURE 0x1702 // GL_TEXTURE - -// Primitive assembly draw modes -#define RL_LINES 0x0001 // GL_LINES -#define RL_TRIANGLES 0x0004 // GL_TRIANGLES -#define RL_QUADS 0x0007 // GL_QUADS - -// GL equivalent data types -#define RL_UNSIGNED_BYTE 0x1401 // GL_UNSIGNED_BYTE -#define RL_FLOAT 0x1406 // GL_FLOAT - -// GL buffer usage hint -#define RL_STREAM_DRAW 0x88E0 // GL_STREAM_DRAW -#define RL_STREAM_READ 0x88E1 // GL_STREAM_READ -#define RL_STREAM_COPY 0x88E2 // GL_STREAM_COPY -#define RL_STATIC_DRAW 0x88E4 // GL_STATIC_DRAW -#define RL_STATIC_READ 0x88E5 // GL_STATIC_READ -#define RL_STATIC_COPY 0x88E6 // GL_STATIC_COPY -#define RL_DYNAMIC_DRAW 0x88E8 // GL_DYNAMIC_DRAW -#define RL_DYNAMIC_READ 0x88E9 // GL_DYNAMIC_READ -#define RL_DYNAMIC_COPY 0x88EA // GL_DYNAMIC_COPY - -// GL Shader type -#define RL_FRAGMENT_SHADER 0x8B30 // GL_FRAGMENT_SHADER -#define RL_VERTEX_SHADER 0x8B31 // GL_VERTEX_SHADER -#define RL_COMPUTE_SHADER 0x91B9 // GL_COMPUTE_SHADER - -// GL blending factors -#define RL_ZERO 0 // GL_ZERO -#define RL_ONE 1 // GL_ONE -#define RL_SRC_COLOR 0x0300 // GL_SRC_COLOR -#define RL_ONE_MINUS_SRC_COLOR 0x0301 // GL_ONE_MINUS_SRC_COLOR -#define RL_SRC_ALPHA 0x0302 // GL_SRC_ALPHA -#define RL_ONE_MINUS_SRC_ALPHA 0x0303 // GL_ONE_MINUS_SRC_ALPHA -#define RL_DST_ALPHA 0x0304 // GL_DST_ALPHA -#define RL_ONE_MINUS_DST_ALPHA 0x0305 // GL_ONE_MINUS_DST_ALPHA -#define RL_DST_COLOR 0x0306 // GL_DST_COLOR -#define RL_ONE_MINUS_DST_COLOR 0x0307 // GL_ONE_MINUS_DST_COLOR -#define RL_SRC_ALPHA_SATURATE 0x0308 // GL_SRC_ALPHA_SATURATE -#define RL_CONSTANT_COLOR 0x8001 // GL_CONSTANT_COLOR -#define RL_ONE_MINUS_CONSTANT_COLOR 0x8002 // GL_ONE_MINUS_CONSTANT_COLOR -#define RL_CONSTANT_ALPHA 0x8003 // GL_CONSTANT_ALPHA -#define RL_ONE_MINUS_CONSTANT_ALPHA 0x8004 // GL_ONE_MINUS_CONSTANT_ALPHA - -// GL blending functions/equations -#define RL_FUNC_ADD 0x8006 // GL_FUNC_ADD -#define RL_MIN 0x8007 // GL_MIN -#define RL_MAX 0x8008 // GL_MAX -#define RL_FUNC_SUBTRACT 0x800A // GL_FUNC_SUBTRACT -#define RL_FUNC_REVERSE_SUBTRACT 0x800B // GL_FUNC_REVERSE_SUBTRACT -#define RL_BLEND_EQUATION 0x8009 // GL_BLEND_EQUATION -#define RL_BLEND_EQUATION_RGB 0x8009 // GL_BLEND_EQUATION_RGB // (Same as BLEND_EQUATION) -#define RL_BLEND_EQUATION_ALPHA 0x883D // GL_BLEND_EQUATION_ALPHA -#define RL_BLEND_DST_RGB 0x80C8 // GL_BLEND_DST_RGB -#define RL_BLEND_SRC_RGB 0x80C9 // GL_BLEND_SRC_RGB -#define RL_BLEND_DST_ALPHA 0x80CA // GL_BLEND_DST_ALPHA -#define RL_BLEND_SRC_ALPHA 0x80CB // GL_BLEND_SRC_ALPHA -#define RL_BLEND_COLOR 0x8005 // GL_BLEND_COLOR - -#define RL_READ_FRAMEBUFFER 0x8CA8 // GL_READ_FRAMEBUFFER -#define RL_DRAW_FRAMEBUFFER 0x8CA9 // GL_DRAW_FRAMEBUFFER - -// Default shader vertex attribute locations -#ifndef RL_DEFAULT_SHADER_ATTRIB_LOCATION_POSITION - #define RL_DEFAULT_SHADER_ATTRIB_LOCATION_POSITION 0 -#endif -#ifndef RL_DEFAULT_SHADER_ATTRIB_LOCATION_TEXCOORD - #define RL_DEFAULT_SHADER_ATTRIB_LOCATION_TEXCOORD 1 -#endif -#ifndef RL_DEFAULT_SHADER_ATTRIB_LOCATION_NORMAL - #define RL_DEFAULT_SHADER_ATTRIB_LOCATION_NORMAL 2 -#endif -#ifndef RL_DEFAULT_SHADER_ATTRIB_LOCATION_COLOR - #define RL_DEFAULT_SHADER_ATTRIB_LOCATION_COLOR 3 -#endif - #ifndef RL_DEFAULT_SHADER_ATTRIB_LOCATION_TANGENT -#define RL_DEFAULT_SHADER_ATTRIB_LOCATION_TANGENT 4 -#endif -#ifndef RL_DEFAULT_SHADER_ATTRIB_LOCATION_TEXCOORD2 - #define RL_DEFAULT_SHADER_ATTRIB_LOCATION_TEXCOORD2 5 -#endif -#ifndef RL_DEFAULT_SHADER_ATTRIB_LOCATION_INDICES - #define RL_DEFAULT_SHADER_ATTRIB_LOCATION_INDICES 6 -#endif -#ifdef RL_SUPPORT_MESH_GPU_SKINNING -#ifndef RL_DEFAULT_SHADER_ATTRIB_LOCATION_BONEIDS - #define RL_DEFAULT_SHADER_ATTRIB_LOCATION_BONEIDS 7 -#endif -#ifndef RL_DEFAULT_SHADER_ATTRIB_LOCATION_BONEWEIGHTS - #define RL_DEFAULT_SHADER_ATTRIB_LOCATION_BONEWEIGHTS 8 -#endif -#endif - -//---------------------------------------------------------------------------------- -// Types and Structures Definition -//---------------------------------------------------------------------------------- -#if (defined(__STDC__) && __STDC_VERSION__ >= 199901L) || (defined(_MSC_VER) && _MSC_VER >= 1800) - #include -#elif !defined(__cplusplus) && !defined(bool) && !defined(RL_BOOL_TYPE) - // Boolean type -typedef enum bool { false = 0, true = !false } bool; -#endif - -#if !defined(RL_MATRIX_TYPE) -// Matrix, 4x4 components, column major, OpenGL style, right handed -typedef struct Matrix { - float m0, m4, m8, m12; // Matrix first row (4 components) - float m1, m5, m9, m13; // Matrix second row (4 components) - float m2, m6, m10, m14; // Matrix third row (4 components) - float m3, m7, m11, m15; // Matrix fourth row (4 components) -} Matrix; -#define RL_MATRIX_TYPE -#endif - -// Dynamic vertex buffers (position + texcoords + colors + indices arrays) -typedef struct rlVertexBuffer { - int elementCount; // Number of elements in the buffer (QUADS) - - float *vertices; // Vertex position (XYZ - 3 components per vertex) (shader-location = 0) - float *texcoords; // Vertex texture coordinates (UV - 2 components per vertex) (shader-location = 1) - float *normals; // Vertex normal (XYZ - 3 components per vertex) (shader-location = 2) - unsigned char *colors; // Vertex colors (RGBA - 4 components per vertex) (shader-location = 3) -#if defined(GRAPHICS_API_OPENGL_11) || defined(GRAPHICS_API_OPENGL_33) - unsigned int *indices; // Vertex indices (in case vertex data comes indexed) (6 indices per quad) -#endif -#if defined(GRAPHICS_API_OPENGL_ES2) - unsigned short *indices; // Vertex indices (in case vertex data comes indexed) (6 indices per quad) -#endif - unsigned int vaoId; // OpenGL Vertex Array Object id - unsigned int vboId[5]; // OpenGL Vertex Buffer Objects id (5 types of vertex data) -} rlVertexBuffer; - -// Draw call type -// NOTE: Only texture changes register a new draw, other state-change-related elements are not -// used at this moment (vaoId, shaderId, matrices), raylib just forces a batch draw call if any -// of those state-change happens (this is done in core module) -typedef struct rlDrawCall { - int mode; // Drawing mode: LINES, TRIANGLES, QUADS - int vertexCount; // Number of vertex of the draw - int vertexAlignment; // Number of vertex required for index alignment (LINES, TRIANGLES) - //unsigned int vaoId; // Vertex array id to be used on the draw -> Using RLGL.currentBatch->vertexBuffer.vaoId - //unsigned int shaderId; // Shader id to be used on the draw -> Using RLGL.currentShaderId - unsigned int textureId; // Texture id to be used on the draw -> Use to create new draw call if changes - - //Matrix projection; // Projection matrix for this draw -> Using RLGL.projection by default - //Matrix modelview; // Modelview matrix for this draw -> Using RLGL.modelview by default -} rlDrawCall; - -// rlRenderBatch type -typedef struct rlRenderBatch { - int bufferCount; // Number of vertex buffers (multi-buffering support) - int currentBuffer; // Current buffer tracking in case of multi-buffering - rlVertexBuffer *vertexBuffer; // Dynamic buffer(s) for vertex data - - rlDrawCall *draws; // Draw calls array, depends on textureId - int drawCounter; // Draw calls counter - float currentDepth; // Current depth value for next draw -} rlRenderBatch; - -// OpenGL version -typedef enum { - RL_OPENGL_11 = 1, // OpenGL 1.1 - RL_OPENGL_21, // OpenGL 2.1 (GLSL 120) - RL_OPENGL_33, // OpenGL 3.3 (GLSL 330) - RL_OPENGL_43, // OpenGL 4.3 (using GLSL 330) - RL_OPENGL_ES_20, // OpenGL ES 2.0 (GLSL 100) - RL_OPENGL_ES_30 // OpenGL ES 3.0 (GLSL 300 es) -} rlGlVersion; - -// Trace log level -// NOTE: Organized by priority level -typedef enum { - RL_LOG_ALL = 0, // Display all logs - RL_LOG_TRACE, // Trace logging, intended for internal use only - RL_LOG_DEBUG, // Debug logging, used for internal debugging, it should be disabled on release builds - RL_LOG_INFO, // Info logging, used for program execution info - RL_LOG_WARNING, // Warning logging, used on recoverable failures - RL_LOG_ERROR, // Error logging, used on unrecoverable failures - RL_LOG_FATAL, // Fatal logging, used to abort program: exit(EXIT_FAILURE) - RL_LOG_NONE // Disable logging -} rlTraceLogLevel; - -// Texture pixel formats -// NOTE: Support depends on OpenGL version -typedef enum { - RL_PIXELFORMAT_UNCOMPRESSED_GRAYSCALE = 1, // 8 bit per pixel (no alpha) - RL_PIXELFORMAT_UNCOMPRESSED_GRAY_ALPHA, // 8*2 bpp (2 channels) - RL_PIXELFORMAT_UNCOMPRESSED_R5G6B5, // 16 bpp - RL_PIXELFORMAT_UNCOMPRESSED_R8G8B8, // 24 bpp - RL_PIXELFORMAT_UNCOMPRESSED_R5G5B5A1, // 16 bpp (1 bit alpha) - RL_PIXELFORMAT_UNCOMPRESSED_R4G4B4A4, // 16 bpp (4 bit alpha) - RL_PIXELFORMAT_UNCOMPRESSED_R8G8B8A8, // 32 bpp - RL_PIXELFORMAT_UNCOMPRESSED_R32, // 32 bpp (1 channel - float) - RL_PIXELFORMAT_UNCOMPRESSED_R32G32B32, // 32*3 bpp (3 channels - float) - RL_PIXELFORMAT_UNCOMPRESSED_R32G32B32A32, // 32*4 bpp (4 channels - float) - RL_PIXELFORMAT_UNCOMPRESSED_R16, // 16 bpp (1 channel - half float) - RL_PIXELFORMAT_UNCOMPRESSED_R16G16B16, // 16*3 bpp (3 channels - half float) - RL_PIXELFORMAT_UNCOMPRESSED_R16G16B16A16, // 16*4 bpp (4 channels - half float) - RL_PIXELFORMAT_COMPRESSED_DXT1_RGB, // 4 bpp (no alpha) - RL_PIXELFORMAT_COMPRESSED_DXT1_RGBA, // 4 bpp (1 bit alpha) - RL_PIXELFORMAT_COMPRESSED_DXT3_RGBA, // 8 bpp - RL_PIXELFORMAT_COMPRESSED_DXT5_RGBA, // 8 bpp - RL_PIXELFORMAT_COMPRESSED_ETC1_RGB, // 4 bpp - RL_PIXELFORMAT_COMPRESSED_ETC2_RGB, // 4 bpp - RL_PIXELFORMAT_COMPRESSED_ETC2_EAC_RGBA, // 8 bpp - RL_PIXELFORMAT_COMPRESSED_PVRT_RGB, // 4 bpp - RL_PIXELFORMAT_COMPRESSED_PVRT_RGBA, // 4 bpp - RL_PIXELFORMAT_COMPRESSED_ASTC_4x4_RGBA, // 8 bpp - RL_PIXELFORMAT_COMPRESSED_ASTC_8x8_RGBA // 2 bpp -} rlPixelFormat; - -// Texture parameters: filter mode -// NOTE 1: Filtering considers mipmaps if available in the texture -// NOTE 2: Filter is accordingly set for minification and magnification -typedef enum { - RL_TEXTURE_FILTER_POINT = 0, // No filter, just pixel approximation - RL_TEXTURE_FILTER_BILINEAR, // Linear filtering - RL_TEXTURE_FILTER_TRILINEAR, // Trilinear filtering (linear with mipmaps) - RL_TEXTURE_FILTER_ANISOTROPIC_4X, // Anisotropic filtering 4x - RL_TEXTURE_FILTER_ANISOTROPIC_8X, // Anisotropic filtering 8x - RL_TEXTURE_FILTER_ANISOTROPIC_16X, // Anisotropic filtering 16x -} rlTextureFilter; - -// Color blending modes (pre-defined) -typedef enum { - RL_BLEND_ALPHA = 0, // Blend textures considering alpha (default) - RL_BLEND_ADDITIVE, // Blend textures adding colors - RL_BLEND_MULTIPLIED, // Blend textures multiplying colors - RL_BLEND_ADD_COLORS, // Blend textures adding colors (alternative) - RL_BLEND_SUBTRACT_COLORS, // Blend textures subtracting colors (alternative) - RL_BLEND_ALPHA_PREMULTIPLY, // Blend premultiplied textures considering alpha - RL_BLEND_CUSTOM, // Blend textures using custom src/dst factors (use rlSetBlendFactors()) - RL_BLEND_CUSTOM_SEPARATE // Blend textures using custom src/dst factors (use rlSetBlendFactorsSeparate()) -} rlBlendMode; - -// Shader location point type -typedef enum { - RL_SHADER_LOC_VERTEX_POSITION = 0, // Shader location: vertex attribute: position - RL_SHADER_LOC_VERTEX_TEXCOORD01, // Shader location: vertex attribute: texcoord01 - RL_SHADER_LOC_VERTEX_TEXCOORD02, // Shader location: vertex attribute: texcoord02 - RL_SHADER_LOC_VERTEX_NORMAL, // Shader location: vertex attribute: normal - RL_SHADER_LOC_VERTEX_TANGENT, // Shader location: vertex attribute: tangent - RL_SHADER_LOC_VERTEX_COLOR, // Shader location: vertex attribute: color - RL_SHADER_LOC_MATRIX_MVP, // Shader location: matrix uniform: model-view-projection - RL_SHADER_LOC_MATRIX_VIEW, // Shader location: matrix uniform: view (camera transform) - RL_SHADER_LOC_MATRIX_PROJECTION, // Shader location: matrix uniform: projection - RL_SHADER_LOC_MATRIX_MODEL, // Shader location: matrix uniform: model (transform) - RL_SHADER_LOC_MATRIX_NORMAL, // Shader location: matrix uniform: normal - RL_SHADER_LOC_VECTOR_VIEW, // Shader location: vector uniform: view - RL_SHADER_LOC_COLOR_DIFFUSE, // Shader location: vector uniform: diffuse color - RL_SHADER_LOC_COLOR_SPECULAR, // Shader location: vector uniform: specular color - RL_SHADER_LOC_COLOR_AMBIENT, // Shader location: vector uniform: ambient color - RL_SHADER_LOC_MAP_ALBEDO, // Shader location: sampler2d texture: albedo (same as: RL_SHADER_LOC_MAP_DIFFUSE) - RL_SHADER_LOC_MAP_METALNESS, // Shader location: sampler2d texture: metalness (same as: RL_SHADER_LOC_MAP_SPECULAR) - RL_SHADER_LOC_MAP_NORMAL, // Shader location: sampler2d texture: normal - RL_SHADER_LOC_MAP_ROUGHNESS, // Shader location: sampler2d texture: roughness - RL_SHADER_LOC_MAP_OCCLUSION, // Shader location: sampler2d texture: occlusion - RL_SHADER_LOC_MAP_EMISSION, // Shader location: sampler2d texture: emission - RL_SHADER_LOC_MAP_HEIGHT, // Shader location: sampler2d texture: height - RL_SHADER_LOC_MAP_CUBEMAP, // Shader location: samplerCube texture: cubemap - RL_SHADER_LOC_MAP_IRRADIANCE, // Shader location: samplerCube texture: irradiance - RL_SHADER_LOC_MAP_PREFILTER, // Shader location: samplerCube texture: prefilter - RL_SHADER_LOC_MAP_BRDF // Shader location: sampler2d texture: brdf -} rlShaderLocationIndex; - -#define RL_SHADER_LOC_MAP_DIFFUSE RL_SHADER_LOC_MAP_ALBEDO -#define RL_SHADER_LOC_MAP_SPECULAR RL_SHADER_LOC_MAP_METALNESS - -// Shader uniform data type -typedef enum { - RL_SHADER_UNIFORM_FLOAT = 0, // Shader uniform type: float - RL_SHADER_UNIFORM_VEC2, // Shader uniform type: vec2 (2 float) - RL_SHADER_UNIFORM_VEC3, // Shader uniform type: vec3 (3 float) - RL_SHADER_UNIFORM_VEC4, // Shader uniform type: vec4 (4 float) - RL_SHADER_UNIFORM_INT, // Shader uniform type: int - RL_SHADER_UNIFORM_IVEC2, // Shader uniform type: ivec2 (2 int) - RL_SHADER_UNIFORM_IVEC3, // Shader uniform type: ivec3 (3 int) - RL_SHADER_UNIFORM_IVEC4, // Shader uniform type: ivec4 (4 int) - RL_SHADER_UNIFORM_UINT, // Shader uniform type: unsigned int - RL_SHADER_UNIFORM_UIVEC2, // Shader uniform type: uivec2 (2 unsigned int) - RL_SHADER_UNIFORM_UIVEC3, // Shader uniform type: uivec3 (3 unsigned int) - RL_SHADER_UNIFORM_UIVEC4, // Shader uniform type: uivec4 (4 unsigned int) - RL_SHADER_UNIFORM_SAMPLER2D // Shader uniform type: sampler2d -} rlShaderUniformDataType; - -// Shader attribute data types -typedef enum { - RL_SHADER_ATTRIB_FLOAT = 0, // Shader attribute type: float - RL_SHADER_ATTRIB_VEC2, // Shader attribute type: vec2 (2 float) - RL_SHADER_ATTRIB_VEC3, // Shader attribute type: vec3 (3 float) - RL_SHADER_ATTRIB_VEC4 // Shader attribute type: vec4 (4 float) -} rlShaderAttributeDataType; - -// Framebuffer attachment type -// NOTE: By default up to 8 color channels defined, but it can be more -typedef enum { - RL_ATTACHMENT_COLOR_CHANNEL0 = 0, // Framebuffer attachment type: color 0 - RL_ATTACHMENT_COLOR_CHANNEL1 = 1, // Framebuffer attachment type: color 1 - RL_ATTACHMENT_COLOR_CHANNEL2 = 2, // Framebuffer attachment type: color 2 - RL_ATTACHMENT_COLOR_CHANNEL3 = 3, // Framebuffer attachment type: color 3 - RL_ATTACHMENT_COLOR_CHANNEL4 = 4, // Framebuffer attachment type: color 4 - RL_ATTACHMENT_COLOR_CHANNEL5 = 5, // Framebuffer attachment type: color 5 - RL_ATTACHMENT_COLOR_CHANNEL6 = 6, // Framebuffer attachment type: color 6 - RL_ATTACHMENT_COLOR_CHANNEL7 = 7, // Framebuffer attachment type: color 7 - RL_ATTACHMENT_DEPTH = 100, // Framebuffer attachment type: depth - RL_ATTACHMENT_STENCIL = 200, // Framebuffer attachment type: stencil -} rlFramebufferAttachType; - -// Framebuffer texture attachment type -typedef enum { - RL_ATTACHMENT_CUBEMAP_POSITIVE_X = 0, // Framebuffer texture attachment type: cubemap, +X side - RL_ATTACHMENT_CUBEMAP_NEGATIVE_X = 1, // Framebuffer texture attachment type: cubemap, -X side - RL_ATTACHMENT_CUBEMAP_POSITIVE_Y = 2, // Framebuffer texture attachment type: cubemap, +Y side - RL_ATTACHMENT_CUBEMAP_NEGATIVE_Y = 3, // Framebuffer texture attachment type: cubemap, -Y side - RL_ATTACHMENT_CUBEMAP_POSITIVE_Z = 4, // Framebuffer texture attachment type: cubemap, +Z side - RL_ATTACHMENT_CUBEMAP_NEGATIVE_Z = 5, // Framebuffer texture attachment type: cubemap, -Z side - RL_ATTACHMENT_TEXTURE2D = 100, // Framebuffer texture attachment type: texture2d - RL_ATTACHMENT_RENDERBUFFER = 200, // Framebuffer texture attachment type: renderbuffer -} rlFramebufferAttachTextureType; - -// Face culling mode -typedef enum { - RL_CULL_FACE_FRONT = 0, - RL_CULL_FACE_BACK -} rlCullMode; - -//------------------------------------------------------------------------------------ -// Functions Declaration - Matrix operations -//------------------------------------------------------------------------------------ - -#if defined(__cplusplus) -extern "C" { // Prevents name mangling of functions -#endif - -RLAPI void rlMatrixMode(int mode); // Choose the current matrix to be transformed -RLAPI void rlPushMatrix(void); // Push the current matrix to stack -RLAPI void rlPopMatrix(void); // Pop latest inserted matrix from stack -RLAPI void rlLoadIdentity(void); // Reset current matrix to identity matrix -RLAPI void rlTranslatef(float x, float y, float z); // Multiply the current matrix by a translation matrix -RLAPI void rlRotatef(float angle, float x, float y, float z); // Multiply the current matrix by a rotation matrix -RLAPI void rlScalef(float x, float y, float z); // Multiply the current matrix by a scaling matrix -RLAPI void rlMultMatrixf(const float *matf); // Multiply the current matrix by another matrix -RLAPI void rlFrustum(double left, double right, double bottom, double top, double znear, double zfar); -RLAPI void rlOrtho(double left, double right, double bottom, double top, double znear, double zfar); -RLAPI void rlViewport(int x, int y, int width, int height); // Set the viewport area -RLAPI void rlSetClipPlanes(double nearPlane, double farPlane); // Set clip planes distances -RLAPI double rlGetCullDistanceNear(void); // Get cull plane distance near -RLAPI double rlGetCullDistanceFar(void); // Get cull plane distance far - -//------------------------------------------------------------------------------------ -// Functions Declaration - Vertex level operations -//------------------------------------------------------------------------------------ -RLAPI void rlBegin(int mode); // Initialize drawing mode (how to organize vertex) -RLAPI void rlEnd(void); // Finish vertex providing -RLAPI void rlVertex2i(int x, int y); // Define one vertex (position) - 2 int -RLAPI void rlVertex2f(float x, float y); // Define one vertex (position) - 2 float -RLAPI void rlVertex3f(float x, float y, float z); // Define one vertex (position) - 3 float -RLAPI void rlTexCoord2f(float x, float y); // Define one vertex (texture coordinate) - 2 float -RLAPI void rlNormal3f(float x, float y, float z); // Define one vertex (normal) - 3 float -RLAPI void rlColor4ub(unsigned char r, unsigned char g, unsigned char b, unsigned char a); // Define one vertex (color) - 4 byte -RLAPI void rlColor3f(float x, float y, float z); // Define one vertex (color) - 3 float -RLAPI void rlColor4f(float x, float y, float z, float w); // Define one vertex (color) - 4 float - -//------------------------------------------------------------------------------------ -// Functions Declaration - OpenGL style functions (common to 1.1, 3.3+, ES2) -// NOTE: This functions are used to completely abstract raylib code from OpenGL layer, -// some of them are direct wrappers over OpenGL calls, some others are custom -//------------------------------------------------------------------------------------ - -// Vertex buffers state -RLAPI bool rlEnableVertexArray(unsigned int vaoId); // Enable vertex array (VAO, if supported) -RLAPI void rlDisableVertexArray(void); // Disable vertex array (VAO, if supported) -RLAPI void rlEnableVertexBuffer(unsigned int id); // Enable vertex buffer (VBO) -RLAPI void rlDisableVertexBuffer(void); // Disable vertex buffer (VBO) -RLAPI void rlEnableVertexBufferElement(unsigned int id); // Enable vertex buffer element (VBO element) -RLAPI void rlDisableVertexBufferElement(void); // Disable vertex buffer element (VBO element) -RLAPI void rlEnableVertexAttribute(unsigned int index); // Enable vertex attribute index -RLAPI void rlDisableVertexAttribute(unsigned int index); // Disable vertex attribute index -#if defined(GRAPHICS_API_OPENGL_11) -RLAPI void rlEnableStatePointer(int vertexAttribType, void *buffer); // Enable attribute state pointer -RLAPI void rlDisableStatePointer(int vertexAttribType); // Disable attribute state pointer -#endif - -// Textures state -RLAPI void rlActiveTextureSlot(int slot); // Select and active a texture slot -RLAPI void rlEnableTexture(unsigned int id); // Enable texture -RLAPI void rlDisableTexture(void); // Disable texture -RLAPI void rlEnableTextureCubemap(unsigned int id); // Enable texture cubemap -RLAPI void rlDisableTextureCubemap(void); // Disable texture cubemap -RLAPI void rlTextureParameters(unsigned int id, int param, int value); // Set texture parameters (filter, wrap) -RLAPI void rlCubemapParameters(unsigned int id, int param, int value); // Set cubemap parameters (filter, wrap) - -// Shader state -RLAPI void rlEnableShader(unsigned int id); // Enable shader program -RLAPI void rlDisableShader(void); // Disable shader program - -// Framebuffer state -RLAPI void rlEnableFramebuffer(unsigned int id); // Enable render texture (fbo) -RLAPI void rlDisableFramebuffer(void); // Disable render texture (fbo), return to default framebuffer -RLAPI unsigned int rlGetActiveFramebuffer(void); // Get the currently active render texture (fbo), 0 for default framebuffer -RLAPI void rlActiveDrawBuffers(int count); // Activate multiple draw color buffers -RLAPI void rlBlitFramebuffer(int srcX, int srcY, int srcWidth, int srcHeight, int dstX, int dstY, int dstWidth, int dstHeight, int bufferMask); // Blit active framebuffer to main framebuffer -RLAPI void rlBindFramebuffer(unsigned int target, unsigned int framebuffer); // Bind framebuffer (FBO) - -// General render state -RLAPI void rlEnableColorBlend(void); // Enable color blending -RLAPI void rlDisableColorBlend(void); // Disable color blending -RLAPI void rlEnableDepthTest(void); // Enable depth test -RLAPI void rlDisableDepthTest(void); // Disable depth test -RLAPI void rlEnableDepthMask(void); // Enable depth write -RLAPI void rlDisableDepthMask(void); // Disable depth write -RLAPI void rlEnableBackfaceCulling(void); // Enable backface culling -RLAPI void rlDisableBackfaceCulling(void); // Disable backface culling -RLAPI void rlColorMask(bool r, bool g, bool b, bool a); // Color mask control -RLAPI void rlSetCullFace(int mode); // Set face culling mode -RLAPI void rlEnableScissorTest(void); // Enable scissor test -RLAPI void rlDisableScissorTest(void); // Disable scissor test -RLAPI void rlScissor(int x, int y, int width, int height); // Scissor test -RLAPI void rlEnableWireMode(void); // Enable wire mode -RLAPI void rlEnablePointMode(void); // Enable point mode -RLAPI void rlDisableWireMode(void); // Disable wire (and point) mode -RLAPI void rlSetLineWidth(float width); // Set the line drawing width -RLAPI float rlGetLineWidth(void); // Get the line drawing width -RLAPI void rlEnableSmoothLines(void); // Enable line aliasing -RLAPI void rlDisableSmoothLines(void); // Disable line aliasing -RLAPI void rlEnableStereoRender(void); // Enable stereo rendering -RLAPI void rlDisableStereoRender(void); // Disable stereo rendering -RLAPI bool rlIsStereoRenderEnabled(void); // Check if stereo render is enabled - -RLAPI void rlClearColor(unsigned char r, unsigned char g, unsigned char b, unsigned char a); // Clear color buffer with color -RLAPI void rlClearScreenBuffers(void); // Clear used screen buffers (color and depth) -RLAPI void rlCheckErrors(void); // Check and log OpenGL error codes -RLAPI void rlSetBlendMode(int mode); // Set blending mode -RLAPI void rlSetBlendFactors(int glSrcFactor, int glDstFactor, int glEquation); // Set blending mode factor and equation (using OpenGL factors) -RLAPI void rlSetBlendFactorsSeparate(int glSrcRGB, int glDstRGB, int glSrcAlpha, int glDstAlpha, int glEqRGB, int glEqAlpha); // Set blending mode factors and equations separately (using OpenGL factors) - -//------------------------------------------------------------------------------------ -// Functions Declaration - rlgl functionality -//------------------------------------------------------------------------------------ -// rlgl initialization functions -RLAPI void rlglInit(int width, int height); // Initialize rlgl (buffers, shaders, textures, states) -RLAPI void rlglClose(void); // De-initialize rlgl (buffers, shaders, textures) -RLAPI void rlLoadExtensions(void *loader); // Load OpenGL extensions (loader function required) -RLAPI int rlGetVersion(void); // Get current OpenGL version -RLAPI void rlSetFramebufferWidth(int width); // Set current framebuffer width -RLAPI int rlGetFramebufferWidth(void); // Get default framebuffer width -RLAPI void rlSetFramebufferHeight(int height); // Set current framebuffer height -RLAPI int rlGetFramebufferHeight(void); // Get default framebuffer height - -RLAPI unsigned int rlGetTextureIdDefault(void); // Get default texture id -RLAPI unsigned int rlGetShaderIdDefault(void); // Get default shader id -RLAPI int *rlGetShaderLocsDefault(void); // Get default shader locations - -// Render batch management -// NOTE: rlgl provides a default render batch to behave like OpenGL 1.1 immediate mode -// but this render batch API is exposed in case of custom batches are required -RLAPI rlRenderBatch rlLoadRenderBatch(int numBuffers, int bufferElements); // Load a render batch system -RLAPI void rlUnloadRenderBatch(rlRenderBatch batch); // Unload render batch system -RLAPI void rlDrawRenderBatch(rlRenderBatch *batch); // Draw render batch data (Update->Draw->Reset) -RLAPI void rlSetRenderBatchActive(rlRenderBatch *batch); // Set the active render batch for rlgl (NULL for default internal) -RLAPI void rlDrawRenderBatchActive(void); // Update and draw internal render batch -RLAPI bool rlCheckRenderBatchLimit(int vCount); // Check internal buffer overflow for a given number of vertex - -RLAPI void rlSetTexture(unsigned int id); // Set current texture for render batch and check buffers limits - -//------------------------------------------------------------------------------------------------------------------------ - -// Vertex buffers management -RLAPI unsigned int rlLoadVertexArray(void); // Load vertex array (vao) if supported -RLAPI unsigned int rlLoadVertexBuffer(const void *buffer, int size, bool dynamic); // Load a vertex buffer object -RLAPI unsigned int rlLoadVertexBufferElement(const void *buffer, int size, bool dynamic); // Load vertex buffer elements object -RLAPI void rlUpdateVertexBuffer(unsigned int bufferId, const void *data, int dataSize, int offset); // Update vertex buffer object data on GPU buffer -RLAPI void rlUpdateVertexBufferElements(unsigned int id, const void *data, int dataSize, int offset); // Update vertex buffer elements data on GPU buffer -RLAPI void rlUnloadVertexArray(unsigned int vaoId); // Unload vertex array (vao) -RLAPI void rlUnloadVertexBuffer(unsigned int vboId); // Unload vertex buffer object -RLAPI void rlSetVertexAttribute(unsigned int index, int compSize, int type, bool normalized, int stride, int offset); // Set vertex attribute data configuration -RLAPI void rlSetVertexAttributeDivisor(unsigned int index, int divisor); // Set vertex attribute data divisor -RLAPI void rlSetVertexAttributeDefault(int locIndex, const void *value, int attribType, int count); // Set vertex attribute default value, when attribute to provided -RLAPI void rlDrawVertexArray(int offset, int count); // Draw vertex array (currently active vao) -RLAPI void rlDrawVertexArrayElements(int offset, int count, const void *buffer); // Draw vertex array elements -RLAPI void rlDrawVertexArrayInstanced(int offset, int count, int instances); // Draw vertex array (currently active vao) with instancing -RLAPI void rlDrawVertexArrayElementsInstanced(int offset, int count, const void *buffer, int instances); // Draw vertex array elements with instancing - -// Textures management -RLAPI unsigned int rlLoadTexture(const void *data, int width, int height, int format, int mipmapCount); // Load texture data -RLAPI unsigned int rlLoadTextureDepth(int width, int height, bool useRenderBuffer); // Load depth texture/renderbuffer (to be attached to fbo) -RLAPI unsigned int rlLoadTextureCubemap(const void *data, int size, int format, int mipmapCount); // Load texture cubemap data -RLAPI void rlUpdateTexture(unsigned int id, int offsetX, int offsetY, int width, int height, int format, const void *data); // Update texture with new data on GPU -RLAPI void rlGetGlTextureFormats(int format, unsigned int *glInternalFormat, unsigned int *glFormat, unsigned int *glType); // Get OpenGL internal formats -RLAPI const char *rlGetPixelFormatName(unsigned int format); // Get name string for pixel format -RLAPI void rlUnloadTexture(unsigned int id); // Unload texture from GPU memory -RLAPI void rlGenTextureMipmaps(unsigned int id, int width, int height, int format, int *mipmaps); // Generate mipmap data for selected texture -RLAPI void *rlReadTexturePixels(unsigned int id, int width, int height, int format); // Read texture pixel data -RLAPI unsigned char *rlReadScreenPixels(int width, int height); // Read screen pixel data (color buffer) - -// Framebuffer management (fbo) -RLAPI unsigned int rlLoadFramebuffer(void); // Load an empty framebuffer -RLAPI void rlFramebufferAttach(unsigned int fboId, unsigned int texId, int attachType, int texType, int mipLevel); // Attach texture/renderbuffer to a framebuffer -RLAPI bool rlFramebufferComplete(unsigned int id); // Verify framebuffer is complete -RLAPI void rlUnloadFramebuffer(unsigned int id); // Delete framebuffer from GPU - -// Shaders management -RLAPI unsigned int rlLoadShaderCode(const char *vsCode, const char *fsCode); // Load shader from code strings -RLAPI unsigned int rlCompileShader(const char *shaderCode, int type); // Compile custom shader and return shader id (type: RL_VERTEX_SHADER, RL_FRAGMENT_SHADER, RL_COMPUTE_SHADER) -RLAPI unsigned int rlLoadShaderProgram(unsigned int vShaderId, unsigned int fShaderId); // Load custom shader program -RLAPI void rlUnloadShaderProgram(unsigned int id); // Unload shader program -RLAPI int rlGetLocationUniform(unsigned int shaderId, const char *uniformName); // Get shader location uniform -RLAPI int rlGetLocationAttrib(unsigned int shaderId, const char *attribName); // Get shader location attribute -RLAPI void rlSetUniform(int locIndex, const void *value, int uniformType, int count); // Set shader value uniform -RLAPI void rlSetUniformMatrix(int locIndex, Matrix mat); // Set shader value matrix -RLAPI void rlSetUniformMatrices(int locIndex, const Matrix *mat, int count); // Set shader value matrices -RLAPI void rlSetUniformSampler(int locIndex, unsigned int textureId); // Set shader value sampler -RLAPI void rlSetShader(unsigned int id, int *locs); // Set shader currently active (id and locations) - -// Compute shader management -RLAPI unsigned int rlLoadComputeShaderProgram(unsigned int shaderId); // Load compute shader program -RLAPI void rlComputeShaderDispatch(unsigned int groupX, unsigned int groupY, unsigned int groupZ); // Dispatch compute shader (equivalent to *draw* for graphics pipeline) - -// Shader buffer storage object management (ssbo) -RLAPI unsigned int rlLoadShaderBuffer(unsigned int size, const void *data, int usageHint); // Load shader storage buffer object (SSBO) -RLAPI void rlUnloadShaderBuffer(unsigned int ssboId); // Unload shader storage buffer object (SSBO) -RLAPI void rlUpdateShaderBuffer(unsigned int id, const void *data, unsigned int dataSize, unsigned int offset); // Update SSBO buffer data -RLAPI void rlBindShaderBuffer(unsigned int id, unsigned int index); // Bind SSBO buffer -RLAPI void rlReadShaderBuffer(unsigned int id, void *dest, unsigned int count, unsigned int offset); // Read SSBO buffer data (GPU->CPU) -RLAPI void rlCopyShaderBuffer(unsigned int destId, unsigned int srcId, unsigned int destOffset, unsigned int srcOffset, unsigned int count); // Copy SSBO data between buffers -RLAPI unsigned int rlGetShaderBufferSize(unsigned int id); // Get SSBO buffer size - -// Buffer management -RLAPI void rlBindImageTexture(unsigned int id, unsigned int index, int format, bool readonly); // Bind image texture - -// Matrix state management -RLAPI Matrix rlGetMatrixModelview(void); // Get internal modelview matrix -RLAPI Matrix rlGetMatrixProjection(void); // Get internal projection matrix -RLAPI Matrix rlGetMatrixTransform(void); // Get internal accumulated transform matrix -RLAPI Matrix rlGetMatrixProjectionStereo(int eye); // Get internal projection matrix for stereo render (selected eye) -RLAPI Matrix rlGetMatrixViewOffsetStereo(int eye); // Get internal view offset matrix for stereo render (selected eye) -RLAPI void rlSetMatrixProjection(Matrix proj); // Set a custom projection matrix (replaces internal projection matrix) -RLAPI void rlSetMatrixModelview(Matrix view); // Set a custom modelview matrix (replaces internal modelview matrix) -RLAPI void rlSetMatrixProjectionStereo(Matrix right, Matrix left); // Set eyes projection matrices for stereo rendering -RLAPI void rlSetMatrixViewOffsetStereo(Matrix right, Matrix left); // Set eyes view offsets matrices for stereo rendering - -// Quick and dirty cube/quad buffers load->draw->unload -RLAPI void rlLoadDrawCube(void); // Load and draw a cube -RLAPI void rlLoadDrawQuad(void); // Load and draw a quad - -#if defined(__cplusplus) -} -#endif - -#endif // RLGL_H - -/*********************************************************************************** -* -* RLGL IMPLEMENTATION -* -************************************************************************************/ - -#if defined(RLGL_IMPLEMENTATION) - -// Expose OpenGL functions from glad in raylib -#if defined(BUILD_LIBTYPE_SHARED) - #define GLAD_API_CALL_EXPORT - #define GLAD_API_CALL_EXPORT_BUILD -#endif - -#if defined(GRAPHICS_API_OPENGL_11) - #if defined(__APPLE__) - #include // OpenGL 1.1 library for OSX - #include // OpenGL extensions library - #else - // APIENTRY for OpenGL function pointer declarations is required - #if !defined(APIENTRY) - #if defined(_WIN32) - #define APIENTRY __stdcall - #else - #define APIENTRY - #endif - #endif - // WINGDIAPI definition. Some Windows OpenGL headers need it - #if !defined(WINGDIAPI) && defined(_WIN32) - #define WINGDIAPI __declspec(dllimport) - #endif - - #include // OpenGL 1.1 library - #endif -#endif - -#if defined(GRAPHICS_API_OPENGL_33) - #define GLAD_MALLOC RL_MALLOC - #define GLAD_FREE RL_FREE - - #define GLAD_GL_IMPLEMENTATION - #include "external/glad.h" // GLAD extensions loading library, includes OpenGL headers -#endif - -#if defined(GRAPHICS_API_OPENGL_ES3) - #include // OpenGL ES 3.0 library - #define GL_GLEXT_PROTOTYPES - #include // OpenGL ES 2.0 extensions library -#elif defined(GRAPHICS_API_OPENGL_ES2) - // NOTE: OpenGL ES 2.0 can be enabled on Desktop platforms, - // in that case, functions are loaded from a custom glad for OpenGL ES 2.0 - #if defined(PLATFORM_DESKTOP_GLFW) || defined(PLATFORM_DESKTOP_SDL) - #define GLAD_GLES2_IMPLEMENTATION - #include "external/glad_gles2.h" - #else - #define GL_GLEXT_PROTOTYPES - //#include // EGL library -> not required, platform layer - #include // OpenGL ES 2.0 library - #include // OpenGL ES 2.0 extensions library - #endif - - // It seems OpenGL ES 2.0 instancing entry points are not defined on Raspberry Pi - // provided headers (despite being defined in official Khronos GLES2 headers) - #if defined(PLATFORM_DRM) - typedef void (GL_APIENTRYP PFNGLDRAWARRAYSINSTANCEDEXTPROC) (GLenum mode, GLint start, GLsizei count, GLsizei primcount); - typedef void (GL_APIENTRYP PFNGLDRAWELEMENTSINSTANCEDEXTPROC) (GLenum mode, GLsizei count, GLenum type, const void *indices, GLsizei primcount); - typedef void (GL_APIENTRYP PFNGLVERTEXATTRIBDIVISOREXTPROC) (GLuint index, GLuint divisor); - #endif -#endif - -#include // Required for: malloc(), free() -#include // Required for: strcmp(), strlen() [Used in rlglInit(), on extensions loading] -#include // Required for: sqrtf(), sinf(), cosf(), floor(), log() - -//---------------------------------------------------------------------------------- -// Defines and Macros -//---------------------------------------------------------------------------------- -#ifndef PI - #define PI 3.14159265358979323846f -#endif -#ifndef DEG2RAD - #define DEG2RAD (PI/180.0f) -#endif -#ifndef RAD2DEG - #define RAD2DEG (180.0f/PI) -#endif - -#ifndef GL_SHADING_LANGUAGE_VERSION - #define GL_SHADING_LANGUAGE_VERSION 0x8B8C -#endif - -#ifndef GL_COMPRESSED_RGB_S3TC_DXT1_EXT - #define GL_COMPRESSED_RGB_S3TC_DXT1_EXT 0x83F0 -#endif -#ifndef GL_COMPRESSED_RGBA_S3TC_DXT1_EXT - #define GL_COMPRESSED_RGBA_S3TC_DXT1_EXT 0x83F1 -#endif -#ifndef GL_COMPRESSED_RGBA_S3TC_DXT3_EXT - #define GL_COMPRESSED_RGBA_S3TC_DXT3_EXT 0x83F2 -#endif -#ifndef GL_COMPRESSED_RGBA_S3TC_DXT5_EXT - #define GL_COMPRESSED_RGBA_S3TC_DXT5_EXT 0x83F3 -#endif -#ifndef GL_ETC1_RGB8_OES - #define GL_ETC1_RGB8_OES 0x8D64 -#endif -#ifndef GL_COMPRESSED_RGB8_ETC2 - #define GL_COMPRESSED_RGB8_ETC2 0x9274 -#endif -#ifndef GL_COMPRESSED_RGBA8_ETC2_EAC - #define GL_COMPRESSED_RGBA8_ETC2_EAC 0x9278 -#endif -#ifndef GL_COMPRESSED_RGB_PVRTC_4BPPV1_IMG - #define GL_COMPRESSED_RGB_PVRTC_4BPPV1_IMG 0x8C00 -#endif -#ifndef GL_COMPRESSED_RGBA_PVRTC_4BPPV1_IMG - #define GL_COMPRESSED_RGBA_PVRTC_4BPPV1_IMG 0x8C02 -#endif -#ifndef GL_COMPRESSED_RGBA_ASTC_4x4_KHR - #define GL_COMPRESSED_RGBA_ASTC_4x4_KHR 0x93b0 -#endif -#ifndef GL_COMPRESSED_RGBA_ASTC_8x8_KHR - #define GL_COMPRESSED_RGBA_ASTC_8x8_KHR 0x93b7 -#endif - -#ifndef GL_MAX_TEXTURE_MAX_ANISOTROPY_EXT - #define GL_MAX_TEXTURE_MAX_ANISOTROPY_EXT 0x84FF -#endif -#ifndef GL_TEXTURE_MAX_ANISOTROPY_EXT - #define GL_TEXTURE_MAX_ANISOTROPY_EXT 0x84FE -#endif - -#ifndef GL_PROGRAM_POINT_SIZE - #define GL_PROGRAM_POINT_SIZE 0x8642 -#endif - -#ifndef GL_LINE_WIDTH - #define GL_LINE_WIDTH 0x0B21 -#endif - -#if defined(GRAPHICS_API_OPENGL_11) - #define GL_UNSIGNED_SHORT_5_6_5 0x8363 - #define GL_UNSIGNED_SHORT_5_5_5_1 0x8034 - #define GL_UNSIGNED_SHORT_4_4_4_4 0x8033 -#endif - -#if defined(GRAPHICS_API_OPENGL_21) - #define GL_LUMINANCE 0x1909 - #define GL_LUMINANCE_ALPHA 0x190A -#endif - -#if defined(GRAPHICS_API_OPENGL_ES2) - #define glClearDepth glClearDepthf - #if !defined(GRAPHICS_API_OPENGL_ES3) - #define GL_READ_FRAMEBUFFER GL_FRAMEBUFFER - #define GL_DRAW_FRAMEBUFFER GL_FRAMEBUFFER - #endif -#endif - -// Default shader vertex attribute names to set location points -#ifndef RL_DEFAULT_SHADER_ATTRIB_NAME_POSITION - #define RL_DEFAULT_SHADER_ATTRIB_NAME_POSITION "vertexPosition" // Bound by default to shader location: RL_DEFAULT_SHADER_ATTRIB_NAME_POSITION -#endif -#ifndef RL_DEFAULT_SHADER_ATTRIB_NAME_TEXCOORD - #define RL_DEFAULT_SHADER_ATTRIB_NAME_TEXCOORD "vertexTexCoord" // Bound by default to shader location: RL_DEFAULT_SHADER_ATTRIB_NAME_TEXCOORD -#endif -#ifndef RL_DEFAULT_SHADER_ATTRIB_NAME_NORMAL - #define RL_DEFAULT_SHADER_ATTRIB_NAME_NORMAL "vertexNormal" // Bound by default to shader location: RL_DEFAULT_SHADER_ATTRIB_NAME_NORMAL -#endif -#ifndef RL_DEFAULT_SHADER_ATTRIB_NAME_COLOR - #define RL_DEFAULT_SHADER_ATTRIB_NAME_COLOR "vertexColor" // Bound by default to shader location: RL_DEFAULT_SHADER_ATTRIB_NAME_COLOR -#endif -#ifndef RL_DEFAULT_SHADER_ATTRIB_NAME_TANGENT - #define RL_DEFAULT_SHADER_ATTRIB_NAME_TANGENT "vertexTangent" // Bound by default to shader location: RL_DEFAULT_SHADER_ATTRIB_NAME_TANGENT -#endif -#ifndef RL_DEFAULT_SHADER_ATTRIB_NAME_TEXCOORD2 - #define RL_DEFAULT_SHADER_ATTRIB_NAME_TEXCOORD2 "vertexTexCoord2" // Bound by default to shader location: RL_DEFAULT_SHADER_ATTRIB_NAME_TEXCOORD2 -#endif -#ifndef RL_DEFAULT_SHADER_ATTRIB_NAME_BONEIDS - #define RL_DEFAULT_SHADER_ATTRIB_NAME_BONEIDS "vertexBoneIds" // Bound by default to shader location: RL_DEFAULT_SHADER_ATTRIB_NAME_BONEIDS -#endif -#ifndef RL_DEFAULT_SHADER_ATTRIB_NAME_BONEWEIGHTS - #define RL_DEFAULT_SHADER_ATTRIB_NAME_BONEWEIGHTS "vertexBoneWeights" // Bound by default to shader location: RL_DEFAULT_SHADER_ATTRIB_NAME_BONEWEIGHTS -#endif - -#ifndef RL_DEFAULT_SHADER_UNIFORM_NAME_MVP - #define RL_DEFAULT_SHADER_UNIFORM_NAME_MVP "mvp" // model-view-projection matrix -#endif -#ifndef RL_DEFAULT_SHADER_UNIFORM_NAME_VIEW - #define RL_DEFAULT_SHADER_UNIFORM_NAME_VIEW "matView" // view matrix -#endif -#ifndef RL_DEFAULT_SHADER_UNIFORM_NAME_PROJECTION - #define RL_DEFAULT_SHADER_UNIFORM_NAME_PROJECTION "matProjection" // projection matrix -#endif -#ifndef RL_DEFAULT_SHADER_UNIFORM_NAME_MODEL - #define RL_DEFAULT_SHADER_UNIFORM_NAME_MODEL "matModel" // model matrix -#endif -#ifndef RL_DEFAULT_SHADER_UNIFORM_NAME_NORMAL - #define RL_DEFAULT_SHADER_UNIFORM_NAME_NORMAL "matNormal" // normal matrix (transpose(inverse(matModelView)) -#endif -#ifndef RL_DEFAULT_SHADER_UNIFORM_NAME_COLOR - #define RL_DEFAULT_SHADER_UNIFORM_NAME_COLOR "colDiffuse" // color diffuse (base tint color, multiplied by texture color) -#endif -#ifndef RL_DEFAULT_SHADER_UNIFORM_NAME_BONE_MATRICES - #define RL_DEFAULT_SHADER_UNIFORM_NAME_BONE_MATRICES "boneMatrices" // bone matrices -#endif -#ifndef RL_DEFAULT_SHADER_SAMPLER2D_NAME_TEXTURE0 - #define RL_DEFAULT_SHADER_SAMPLER2D_NAME_TEXTURE0 "texture0" // texture0 (texture slot active 0) -#endif -#ifndef RL_DEFAULT_SHADER_SAMPLER2D_NAME_TEXTURE1 - #define RL_DEFAULT_SHADER_SAMPLER2D_NAME_TEXTURE1 "texture1" // texture1 (texture slot active 1) -#endif -#ifndef RL_DEFAULT_SHADER_SAMPLER2D_NAME_TEXTURE2 - #define RL_DEFAULT_SHADER_SAMPLER2D_NAME_TEXTURE2 "texture2" // texture2 (texture slot active 2) -#endif - -//---------------------------------------------------------------------------------- -// Types and Structures Definition -//---------------------------------------------------------------------------------- -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) -typedef struct rlglData { - rlRenderBatch *currentBatch; // Current render batch - rlRenderBatch defaultBatch; // Default internal render batch - - struct { - int vertexCounter; // Current active render batch vertex counter (generic, used for all batches) - float texcoordx, texcoordy; // Current active texture coordinate (added on glVertex*()) - float normalx, normaly, normalz; // Current active normal (added on glVertex*()) - unsigned char colorr, colorg, colorb, colora; // Current active color (added on glVertex*()) - - int currentMatrixMode; // Current matrix mode - Matrix *currentMatrix; // Current matrix pointer - Matrix modelview; // Default modelview matrix - Matrix projection; // Default projection matrix - Matrix transform; // Transform matrix to be used with rlTranslate, rlRotate, rlScale - bool transformRequired; // Require transform matrix application to current draw-call vertex (if required) - Matrix stack[RL_MAX_MATRIX_STACK_SIZE];// Matrix stack for push/pop - int stackCounter; // Matrix stack counter - - unsigned int defaultTextureId; // Default texture used on shapes/poly drawing (required by shader) - unsigned int activeTextureId[RL_DEFAULT_BATCH_MAX_TEXTURE_UNITS]; // Active texture ids to be enabled on batch drawing (0 active by default) - unsigned int defaultVShaderId; // Default vertex shader id (used by default shader program) - unsigned int defaultFShaderId; // Default fragment shader id (used by default shader program) - unsigned int defaultShaderId; // Default shader program id, supports vertex color and diffuse texture - int *defaultShaderLocs; // Default shader locations pointer to be used on rendering - unsigned int currentShaderId; // Current shader id to be used on rendering (by default, defaultShaderId) - int *currentShaderLocs; // Current shader locations pointer to be used on rendering (by default, defaultShaderLocs) - - bool stereoRender; // Stereo rendering flag - Matrix projectionStereo[2]; // VR stereo rendering eyes projection matrices - Matrix viewOffsetStereo[2]; // VR stereo rendering eyes view offset matrices - - // Blending variables - int currentBlendMode; // Blending mode active - int glBlendSrcFactor; // Blending source factor - int glBlendDstFactor; // Blending destination factor - int glBlendEquation; // Blending equation - int glBlendSrcFactorRGB; // Blending source RGB factor - int glBlendDestFactorRGB; // Blending destination RGB factor - int glBlendSrcFactorAlpha; // Blending source alpha factor - int glBlendDestFactorAlpha; // Blending destination alpha factor - int glBlendEquationRGB; // Blending equation for RGB - int glBlendEquationAlpha; // Blending equation for alpha - bool glCustomBlendModeModified; // Custom blending factor and equation modification status - - int framebufferWidth; // Current framebuffer width - int framebufferHeight; // Current framebuffer height - - } State; // Renderer state - struct { - bool vao; // VAO support (OpenGL ES2 could not support VAO extension) (GL_ARB_vertex_array_object) - bool instancing; // Instancing supported (GL_ANGLE_instanced_arrays, GL_EXT_draw_instanced + GL_EXT_instanced_arrays) - bool texNPOT; // NPOT textures full support (GL_ARB_texture_non_power_of_two, GL_OES_texture_npot) - bool texDepth; // Depth textures supported (GL_ARB_depth_texture, GL_OES_depth_texture) - bool texDepthWebGL; // Depth textures supported WebGL specific (GL_WEBGL_depth_texture) - bool texFloat32; // float textures support (32 bit per channel) (GL_OES_texture_float) - bool texFloat16; // half float textures support (16 bit per channel) (GL_OES_texture_half_float) - bool texCompDXT; // DDS texture compression support (GL_EXT_texture_compression_s3tc, GL_WEBGL_compressed_texture_s3tc, GL_WEBKIT_WEBGL_compressed_texture_s3tc) - bool texCompETC1; // ETC1 texture compression support (GL_OES_compressed_ETC1_RGB8_texture, GL_WEBGL_compressed_texture_etc1) - bool texCompETC2; // ETC2/EAC texture compression support (GL_ARB_ES3_compatibility) - bool texCompPVRT; // PVR texture compression support (GL_IMG_texture_compression_pvrtc) - bool texCompASTC; // ASTC texture compression support (GL_KHR_texture_compression_astc_hdr, GL_KHR_texture_compression_astc_ldr) - bool texMirrorClamp; // Clamp mirror wrap mode supported (GL_EXT_texture_mirror_clamp) - bool texAnisoFilter; // Anisotropic texture filtering support (GL_EXT_texture_filter_anisotropic) - bool computeShader; // Compute shaders support (GL_ARB_compute_shader) - bool ssbo; // Shader storage buffer object support (GL_ARB_shader_storage_buffer_object) - - float maxAnisotropyLevel; // Maximum anisotropy level supported (minimum is 2.0f) - int maxDepthBits; // Maximum bits for depth component - - } ExtSupported; // Extensions supported flags -} rlglData; - -typedef void *(*rlglLoadProc)(const char *name); // OpenGL extension functions loader signature (same as GLADloadproc) - -#endif // GRAPHICS_API_OPENGL_33 || GRAPHICS_API_OPENGL_ES2 - -//---------------------------------------------------------------------------------- -// Global Variables Definition -//---------------------------------------------------------------------------------- -static double rlCullDistanceNear = RL_CULL_DISTANCE_NEAR; -static double rlCullDistanceFar = RL_CULL_DISTANCE_FAR; - -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) -static rlglData RLGL = { 0 }; -#endif // GRAPHICS_API_OPENGL_33 || GRAPHICS_API_OPENGL_ES2 - -#if defined(GRAPHICS_API_OPENGL_ES2) && !defined(GRAPHICS_API_OPENGL_ES3) -// NOTE: VAO functionality is exposed through extensions (OES) -static PFNGLGENVERTEXARRAYSOESPROC glGenVertexArrays = NULL; -static PFNGLBINDVERTEXARRAYOESPROC glBindVertexArray = NULL; -static PFNGLDELETEVERTEXARRAYSOESPROC glDeleteVertexArrays = NULL; - -// NOTE: Instancing functionality could also be available through extension -static PFNGLDRAWARRAYSINSTANCEDEXTPROC glDrawArraysInstanced = NULL; -static PFNGLDRAWELEMENTSINSTANCEDEXTPROC glDrawElementsInstanced = NULL; -static PFNGLVERTEXATTRIBDIVISOREXTPROC glVertexAttribDivisor = NULL; -#endif - -//---------------------------------------------------------------------------------- -// Module specific Functions Declaration -//---------------------------------------------------------------------------------- -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) -static void rlLoadShaderDefault(void); // Load default shader -static void rlUnloadShaderDefault(void); // Unload default shader -#if defined(RLGL_SHOW_GL_DETAILS_INFO) -static const char *rlGetCompressedFormatName(int format); // Get compressed format official GL identifier name -#endif // RLGL_SHOW_GL_DETAILS_INFO -#endif // GRAPHICS_API_OPENGL_33 || GRAPHICS_API_OPENGL_ES2 - -static int rlGetPixelDataSize(int width, int height, int format); // Get pixel data size in bytes (image or texture) - -// Auxiliar matrix math functions -typedef struct rl_float16 { - float v[16]; -} rl_float16; -static rl_float16 rlMatrixToFloatV(Matrix mat); // Get float array of matrix data -#define rlMatrixToFloat(mat) (rlMatrixToFloatV(mat).v) // Get float vector for Matrix -static Matrix rlMatrixIdentity(void); // Get identity matrix -static Matrix rlMatrixMultiply(Matrix left, Matrix right); // Multiply two matrices -static Matrix rlMatrixTranspose(Matrix mat); // Transposes provided matrix -static Matrix rlMatrixInvert(Matrix mat); // Invert provided matrix - -//---------------------------------------------------------------------------------- -// Module Functions Definition - Matrix operations -//---------------------------------------------------------------------------------- - -#if defined(GRAPHICS_API_OPENGL_11) -// Fallback to OpenGL 1.1 function calls -//--------------------------------------- -void rlMatrixMode(int mode) -{ - switch (mode) - { - case RL_PROJECTION: glMatrixMode(GL_PROJECTION); break; - case RL_MODELVIEW: glMatrixMode(GL_MODELVIEW); break; - case RL_TEXTURE: glMatrixMode(GL_TEXTURE); break; - default: break; - } -} - -void rlFrustum(double left, double right, double bottom, double top, double znear, double zfar) -{ - glFrustum(left, right, bottom, top, znear, zfar); -} - -void rlOrtho(double left, double right, double bottom, double top, double znear, double zfar) -{ - glOrtho(left, right, bottom, top, znear, zfar); -} - -void rlPushMatrix(void) { glPushMatrix(); } -void rlPopMatrix(void) { glPopMatrix(); } -void rlLoadIdentity(void) { glLoadIdentity(); } -void rlTranslatef(float x, float y, float z) { glTranslatef(x, y, z); } -void rlRotatef(float angle, float x, float y, float z) { glRotatef(angle, x, y, z); } -void rlScalef(float x, float y, float z) { glScalef(x, y, z); } -void rlMultMatrixf(const float *matf) { glMultMatrixf(matf); } -#endif -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) -// Choose the current matrix to be transformed -void rlMatrixMode(int mode) -{ - if (mode == RL_PROJECTION) RLGL.State.currentMatrix = &RLGL.State.projection; - else if (mode == RL_MODELVIEW) RLGL.State.currentMatrix = &RLGL.State.modelview; - //else if (mode == RL_TEXTURE) // Not supported - - RLGL.State.currentMatrixMode = mode; -} - -// Push the current matrix into RLGL.State.stack -void rlPushMatrix(void) -{ - if (RLGL.State.stackCounter >= RL_MAX_MATRIX_STACK_SIZE) TRACELOG(RL_LOG_ERROR, "RLGL: Matrix stack overflow (RL_MAX_MATRIX_STACK_SIZE)"); - - if (RLGL.State.currentMatrixMode == RL_MODELVIEW) - { - RLGL.State.transformRequired = true; - RLGL.State.currentMatrix = &RLGL.State.transform; - } - - RLGL.State.stack[RLGL.State.stackCounter] = *RLGL.State.currentMatrix; - RLGL.State.stackCounter++; -} - -// Pop lattest inserted matrix from RLGL.State.stack -void rlPopMatrix(void) -{ - if (RLGL.State.stackCounter > 0) - { - Matrix mat = RLGL.State.stack[RLGL.State.stackCounter - 1]; - *RLGL.State.currentMatrix = mat; - RLGL.State.stackCounter--; - } - - if ((RLGL.State.stackCounter == 0) && (RLGL.State.currentMatrixMode == RL_MODELVIEW)) - { - RLGL.State.currentMatrix = &RLGL.State.modelview; - RLGL.State.transformRequired = false; - } -} - -// Reset current matrix to identity matrix -void rlLoadIdentity(void) -{ - *RLGL.State.currentMatrix = rlMatrixIdentity(); -} - -// Multiply the current matrix by a translation matrix -void rlTranslatef(float x, float y, float z) -{ - Matrix matTranslation = { - 1.0f, 0.0f, 0.0f, x, - 0.0f, 1.0f, 0.0f, y, - 0.0f, 0.0f, 1.0f, z, - 0.0f, 0.0f, 0.0f, 1.0f - }; - - // NOTE: We transpose matrix with multiplication order - *RLGL.State.currentMatrix = rlMatrixMultiply(matTranslation, *RLGL.State.currentMatrix); -} - -// Multiply the current matrix by a rotation matrix -// NOTE: The provided angle must be in degrees -void rlRotatef(float angle, float x, float y, float z) -{ - Matrix matRotation = rlMatrixIdentity(); - - // Axis vector (x, y, z) normalization - float lengthSquared = x*x + y*y + z*z; - if ((lengthSquared != 1.0f) && (lengthSquared != 0.0f)) - { - float inverseLength = 1.0f/sqrtf(lengthSquared); - x *= inverseLength; - y *= inverseLength; - z *= inverseLength; - } - - // Rotation matrix generation - float sinres = sinf(DEG2RAD*angle); - float cosres = cosf(DEG2RAD*angle); - float t = 1.0f - cosres; - - matRotation.m0 = x*x*t + cosres; - matRotation.m1 = y*x*t + z*sinres; - matRotation.m2 = z*x*t - y*sinres; - matRotation.m3 = 0.0f; - - matRotation.m4 = x*y*t - z*sinres; - matRotation.m5 = y*y*t + cosres; - matRotation.m6 = z*y*t + x*sinres; - matRotation.m7 = 0.0f; - - matRotation.m8 = x*z*t + y*sinres; - matRotation.m9 = y*z*t - x*sinres; - matRotation.m10 = z*z*t + cosres; - matRotation.m11 = 0.0f; - - matRotation.m12 = 0.0f; - matRotation.m13 = 0.0f; - matRotation.m14 = 0.0f; - matRotation.m15 = 1.0f; - - // NOTE: We transpose matrix with multiplication order - *RLGL.State.currentMatrix = rlMatrixMultiply(matRotation, *RLGL.State.currentMatrix); -} - -// Multiply the current matrix by a scaling matrix -void rlScalef(float x, float y, float z) -{ - Matrix matScale = { - x, 0.0f, 0.0f, 0.0f, - 0.0f, y, 0.0f, 0.0f, - 0.0f, 0.0f, z, 0.0f, - 0.0f, 0.0f, 0.0f, 1.0f - }; - - // NOTE: We transpose matrix with multiplication order - *RLGL.State.currentMatrix = rlMatrixMultiply(matScale, *RLGL.State.currentMatrix); -} - -// Multiply the current matrix by another matrix -void rlMultMatrixf(const float *matf) -{ - // Matrix creation from array - Matrix mat = { matf[0], matf[4], matf[8], matf[12], - matf[1], matf[5], matf[9], matf[13], - matf[2], matf[6], matf[10], matf[14], - matf[3], matf[7], matf[11], matf[15] }; - - *RLGL.State.currentMatrix = rlMatrixMultiply(mat, *RLGL.State.currentMatrix); -} - -// Multiply the current matrix by a perspective matrix generated by parameters -void rlFrustum(double left, double right, double bottom, double top, double znear, double zfar) -{ - Matrix matFrustum = { 0 }; - - float rl = (float)(right - left); - float tb = (float)(top - bottom); - float fn = (float)(zfar - znear); - - matFrustum.m0 = ((float) znear*2.0f)/rl; - matFrustum.m1 = 0.0f; - matFrustum.m2 = 0.0f; - matFrustum.m3 = 0.0f; - - matFrustum.m4 = 0.0f; - matFrustum.m5 = ((float) znear*2.0f)/tb; - matFrustum.m6 = 0.0f; - matFrustum.m7 = 0.0f; - - matFrustum.m8 = ((float)right + (float)left)/rl; - matFrustum.m9 = ((float)top + (float)bottom)/tb; - matFrustum.m10 = -((float)zfar + (float)znear)/fn; - matFrustum.m11 = -1.0f; - - matFrustum.m12 = 0.0f; - matFrustum.m13 = 0.0f; - matFrustum.m14 = -((float)zfar*(float)znear*2.0f)/fn; - matFrustum.m15 = 0.0f; - - *RLGL.State.currentMatrix = rlMatrixMultiply(*RLGL.State.currentMatrix, matFrustum); -} - -// Multiply the current matrix by an orthographic matrix generated by parameters -void rlOrtho(double left, double right, double bottom, double top, double znear, double zfar) -{ - // NOTE: If left-right and top-botton values are equal it could create a division by zero, - // response to it is platform/compiler dependant - Matrix matOrtho = { 0 }; - - float rl = (float)(right - left); - float tb = (float)(top - bottom); - float fn = (float)(zfar - znear); - - matOrtho.m0 = 2.0f/rl; - matOrtho.m1 = 0.0f; - matOrtho.m2 = 0.0f; - matOrtho.m3 = 0.0f; - matOrtho.m4 = 0.0f; - matOrtho.m5 = 2.0f/tb; - matOrtho.m6 = 0.0f; - matOrtho.m7 = 0.0f; - matOrtho.m8 = 0.0f; - matOrtho.m9 = 0.0f; - matOrtho.m10 = -2.0f/fn; - matOrtho.m11 = 0.0f; - matOrtho.m12 = -((float)left + (float)right)/rl; - matOrtho.m13 = -((float)top + (float)bottom)/tb; - matOrtho.m14 = -((float)zfar + (float)znear)/fn; - matOrtho.m15 = 1.0f; - - *RLGL.State.currentMatrix = rlMatrixMultiply(*RLGL.State.currentMatrix, matOrtho); -} -#endif - -// Set the viewport area (transformation from normalized device coordinates to window coordinates) -// NOTE: We store current viewport dimensions -void rlViewport(int x, int y, int width, int height) -{ - glViewport(x, y, width, height); -} - -// Set clip planes distances -void rlSetClipPlanes(double nearPlane, double farPlane) -{ - rlCullDistanceNear = nearPlane; - rlCullDistanceFar = farPlane; -} - -// Get cull plane distance near -double rlGetCullDistanceNear(void) -{ - return rlCullDistanceNear; -} - -// Get cull plane distance far -double rlGetCullDistanceFar(void) -{ - return rlCullDistanceFar; -} - -//---------------------------------------------------------------------------------- -// Module Functions Definition - Vertex level operations -//---------------------------------------------------------------------------------- -#if defined(GRAPHICS_API_OPENGL_11) -// Fallback to OpenGL 1.1 function calls -//--------------------------------------- -void rlBegin(int mode) -{ - switch (mode) - { - case RL_LINES: glBegin(GL_LINES); break; - case RL_TRIANGLES: glBegin(GL_TRIANGLES); break; - case RL_QUADS: glBegin(GL_QUADS); break; - default: break; - } -} - -void rlEnd(void) { glEnd(); } -void rlVertex2i(int x, int y) { glVertex2i(x, y); } -void rlVertex2f(float x, float y) { glVertex2f(x, y); } -void rlVertex3f(float x, float y, float z) { glVertex3f(x, y, z); } -void rlTexCoord2f(float x, float y) { glTexCoord2f(x, y); } -void rlNormal3f(float x, float y, float z) { glNormal3f(x, y, z); } -void rlColor4ub(unsigned char r, unsigned char g, unsigned char b, unsigned char a) { glColor4ub(r, g, b, a); } -void rlColor3f(float x, float y, float z) { glColor3f(x, y, z); } -void rlColor4f(float x, float y, float z, float w) { glColor4f(x, y, z, w); } -#endif -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) -// Initialize drawing mode (how to organize vertex) -void rlBegin(int mode) -{ - // Draw mode can be RL_LINES, RL_TRIANGLES and RL_QUADS - // NOTE: In all three cases, vertex are accumulated over default internal vertex buffer - if (RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].mode != mode) - { - if (RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].vertexCount > 0) - { - // Make sure current RLGL.currentBatch->draws[i].vertexCount is aligned a multiple of 4, - // that way, following QUADS drawing will keep aligned with index processing - // It implies adding some extra alignment vertex at the end of the draw, - // those vertex are not processed but they are considered as an additional offset - // for the next set of vertex to be drawn - if (RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].mode == RL_LINES) RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].vertexAlignment = ((RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].vertexCount < 4)? RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].vertexCount : RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].vertexCount%4); - else if (RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].mode == RL_TRIANGLES) RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].vertexAlignment = ((RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].vertexCount < 4)? 1 : (4 - (RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].vertexCount%4))); - else RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].vertexAlignment = 0; - - if (!rlCheckRenderBatchLimit(RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].vertexAlignment)) - { - RLGL.State.vertexCounter += RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].vertexAlignment; - RLGL.currentBatch->drawCounter++; - } - } - - if (RLGL.currentBatch->drawCounter >= RL_DEFAULT_BATCH_DRAWCALLS) rlDrawRenderBatch(RLGL.currentBatch); - - RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].mode = mode; - RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].vertexCount = 0; - RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].textureId = RLGL.State.defaultTextureId; - } -} - -// Finish vertex providing -void rlEnd(void) -{ - // NOTE: Depth increment is dependant on rlOrtho(): z-near and z-far values, - // as well as depth buffer bit-depth (16bit or 24bit or 32bit) - // Correct increment formula would be: depthInc = (zfar - znear)/pow(2, bits) - RLGL.currentBatch->currentDepth += (1.0f/20000.0f); -} - -// Define one vertex (position) -// NOTE: Vertex position data is the basic information required for drawing -void rlVertex3f(float x, float y, float z) -{ - float tx = x; - float ty = y; - float tz = z; - - // Transform provided vector if required - if (RLGL.State.transformRequired) - { - tx = RLGL.State.transform.m0*x + RLGL.State.transform.m4*y + RLGL.State.transform.m8*z + RLGL.State.transform.m12; - ty = RLGL.State.transform.m1*x + RLGL.State.transform.m5*y + RLGL.State.transform.m9*z + RLGL.State.transform.m13; - tz = RLGL.State.transform.m2*x + RLGL.State.transform.m6*y + RLGL.State.transform.m10*z + RLGL.State.transform.m14; - } - - // WARNING: We can't break primitives when launching a new batch - // RL_LINES comes in pairs, RL_TRIANGLES come in groups of 3 vertices and RL_QUADS come in groups of 4 vertices - // We must check current draw.mode when a new vertex is required and finish the batch only if the draw.mode draw.vertexCount is %2, %3 or %4 - if (RLGL.State.vertexCounter > (RLGL.currentBatch->vertexBuffer[RLGL.currentBatch->currentBuffer].elementCount*4 - 4)) - { - if ((RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].mode == RL_LINES) && - (RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].vertexCount%2 == 0)) - { - // Reached the maximum number of vertices for RL_LINES drawing - // Launch a draw call but keep current state for next vertices comming - // NOTE: We add +1 vertex to the check for security - rlCheckRenderBatchLimit(2 + 1); - } - else if ((RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].mode == RL_TRIANGLES) && - (RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].vertexCount%3 == 0)) - { - rlCheckRenderBatchLimit(3 + 1); - } - else if ((RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].mode == RL_QUADS) && - (RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].vertexCount%4 == 0)) - { - rlCheckRenderBatchLimit(4 + 1); - } - } - - // Add vertices - RLGL.currentBatch->vertexBuffer[RLGL.currentBatch->currentBuffer].vertices[3*RLGL.State.vertexCounter] = tx; - RLGL.currentBatch->vertexBuffer[RLGL.currentBatch->currentBuffer].vertices[3*RLGL.State.vertexCounter + 1] = ty; - RLGL.currentBatch->vertexBuffer[RLGL.currentBatch->currentBuffer].vertices[3*RLGL.State.vertexCounter + 2] = tz; - - // Add current texcoord - RLGL.currentBatch->vertexBuffer[RLGL.currentBatch->currentBuffer].texcoords[2*RLGL.State.vertexCounter] = RLGL.State.texcoordx; - RLGL.currentBatch->vertexBuffer[RLGL.currentBatch->currentBuffer].texcoords[2*RLGL.State.vertexCounter + 1] = RLGL.State.texcoordy; - - // Add current normal - RLGL.currentBatch->vertexBuffer[RLGL.currentBatch->currentBuffer].normals[3*RLGL.State.vertexCounter] = RLGL.State.normalx; - RLGL.currentBatch->vertexBuffer[RLGL.currentBatch->currentBuffer].normals[3*RLGL.State.vertexCounter + 1] = RLGL.State.normaly; - RLGL.currentBatch->vertexBuffer[RLGL.currentBatch->currentBuffer].normals[3*RLGL.State.vertexCounter + 2] = RLGL.State.normalz; - - // Add current color - RLGL.currentBatch->vertexBuffer[RLGL.currentBatch->currentBuffer].colors[4*RLGL.State.vertexCounter] = RLGL.State.colorr; - RLGL.currentBatch->vertexBuffer[RLGL.currentBatch->currentBuffer].colors[4*RLGL.State.vertexCounter + 1] = RLGL.State.colorg; - RLGL.currentBatch->vertexBuffer[RLGL.currentBatch->currentBuffer].colors[4*RLGL.State.vertexCounter + 2] = RLGL.State.colorb; - RLGL.currentBatch->vertexBuffer[RLGL.currentBatch->currentBuffer].colors[4*RLGL.State.vertexCounter + 3] = RLGL.State.colora; - - RLGL.State.vertexCounter++; - RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].vertexCount++; -} - -// Define one vertex (position) -void rlVertex2f(float x, float y) -{ - rlVertex3f(x, y, RLGL.currentBatch->currentDepth); -} - -// Define one vertex (position) -void rlVertex2i(int x, int y) -{ - rlVertex3f((float)x, (float)y, RLGL.currentBatch->currentDepth); -} - -// Define one vertex (texture coordinate) -// NOTE: Texture coordinates are limited to QUADS only -void rlTexCoord2f(float x, float y) -{ - RLGL.State.texcoordx = x; - RLGL.State.texcoordy = y; -} - -// Define one vertex (normal) -// NOTE: Normals limited to TRIANGLES only? -void rlNormal3f(float x, float y, float z) -{ - float normalx = x; - float normaly = y; - float normalz = z; - if (RLGL.State.transformRequired) - { - normalx = RLGL.State.transform.m0*x + RLGL.State.transform.m4*y + RLGL.State.transform.m8*z; - normaly = RLGL.State.transform.m1*x + RLGL.State.transform.m5*y + RLGL.State.transform.m9*z; - normalz = RLGL.State.transform.m2*x + RLGL.State.transform.m6*y + RLGL.State.transform.m10*z; - } - float length = sqrtf(normalx*normalx + normaly*normaly + normalz*normalz); - if (length != 0.0f) - { - float ilength = 1.0f/length; - normalx *= ilength; - normaly *= ilength; - normalz *= ilength; - } - RLGL.State.normalx = normalx; - RLGL.State.normaly = normaly; - RLGL.State.normalz = normalz; -} - -// Define one vertex (color) -void rlColor4ub(unsigned char x, unsigned char y, unsigned char z, unsigned char w) -{ - RLGL.State.colorr = x; - RLGL.State.colorg = y; - RLGL.State.colorb = z; - RLGL.State.colora = w; -} - -// Define one vertex (color) -void rlColor4f(float r, float g, float b, float a) -{ - rlColor4ub((unsigned char)(r*255), (unsigned char)(g*255), (unsigned char)(b*255), (unsigned char)(a*255)); -} - -// Define one vertex (color) -void rlColor3f(float x, float y, float z) -{ - rlColor4ub((unsigned char)(x*255), (unsigned char)(y*255), (unsigned char)(z*255), 255); -} - -#endif - -//-------------------------------------------------------------------------------------- -// Module Functions Definition - OpenGL style functions (common to 1.1, 3.3+, ES2) -//-------------------------------------------------------------------------------------- - -// Set current texture to use -void rlSetTexture(unsigned int id) -{ - if (id == 0) - { -#if defined(GRAPHICS_API_OPENGL_11) - rlDisableTexture(); -#else - // NOTE: If quads batch limit is reached, we force a draw call and next batch starts - if (RLGL.State.vertexCounter >= - RLGL.currentBatch->vertexBuffer[RLGL.currentBatch->currentBuffer].elementCount*4) - { - rlDrawRenderBatch(RLGL.currentBatch); - } -#endif - } - else - { -#if defined(GRAPHICS_API_OPENGL_11) - rlEnableTexture(id); -#else - if (RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].textureId != id) - { - if (RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].vertexCount > 0) - { - // Make sure current RLGL.currentBatch->draws[i].vertexCount is aligned a multiple of 4, - // that way, following QUADS drawing will keep aligned with index processing - // It implies adding some extra alignment vertex at the end of the draw, - // those vertex are not processed but they are considered as an additional offset - // for the next set of vertex to be drawn - if (RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].mode == RL_LINES) RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].vertexAlignment = ((RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].vertexCount < 4)? RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].vertexCount : RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].vertexCount%4); - else if (RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].mode == RL_TRIANGLES) RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].vertexAlignment = ((RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].vertexCount < 4)? 1 : (4 - (RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].vertexCount%4))); - else RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].vertexAlignment = 0; - - if (!rlCheckRenderBatchLimit(RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].vertexAlignment)) - { - RLGL.State.vertexCounter += RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].vertexAlignment; - - RLGL.currentBatch->drawCounter++; - } - } - - if (RLGL.currentBatch->drawCounter >= RL_DEFAULT_BATCH_DRAWCALLS) rlDrawRenderBatch(RLGL.currentBatch); - - RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].textureId = id; - RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].vertexCount = 0; - } -#endif - } -} - -// Select and active a texture slot -void rlActiveTextureSlot(int slot) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - glActiveTexture(GL_TEXTURE0 + slot); -#endif -} - -// Enable texture -void rlEnableTexture(unsigned int id) -{ -#if defined(GRAPHICS_API_OPENGL_11) - glEnable(GL_TEXTURE_2D); -#endif - glBindTexture(GL_TEXTURE_2D, id); -} - -// Disable texture -void rlDisableTexture(void) -{ -#if defined(GRAPHICS_API_OPENGL_11) - glDisable(GL_TEXTURE_2D); -#endif - glBindTexture(GL_TEXTURE_2D, 0); -} - -// Enable texture cubemap -void rlEnableTextureCubemap(unsigned int id) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - glBindTexture(GL_TEXTURE_CUBE_MAP, id); -#endif -} - -// Disable texture cubemap -void rlDisableTextureCubemap(void) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - glBindTexture(GL_TEXTURE_CUBE_MAP, 0); -#endif -} - -// Set texture parameters (wrap mode/filter mode) -void rlTextureParameters(unsigned int id, int param, int value) -{ - glBindTexture(GL_TEXTURE_2D, id); - -#if !defined(GRAPHICS_API_OPENGL_11) - // Reset anisotropy filter, in case it was set - glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_MAX_ANISOTROPY_EXT, 1.0f); -#endif - - switch (param) - { - case RL_TEXTURE_WRAP_S: - case RL_TEXTURE_WRAP_T: - { - if (value == RL_TEXTURE_WRAP_MIRROR_CLAMP) - { -#if !defined(GRAPHICS_API_OPENGL_11) - if (RLGL.ExtSupported.texMirrorClamp) glTexParameteri(GL_TEXTURE_2D, param, value); - else TRACELOG(RL_LOG_WARNING, "GL: Clamp mirror wrap mode not supported (GL_MIRROR_CLAMP_EXT)"); -#endif - } - else glTexParameteri(GL_TEXTURE_2D, param, value); - - } break; - case RL_TEXTURE_MAG_FILTER: - case RL_TEXTURE_MIN_FILTER: glTexParameteri(GL_TEXTURE_2D, param, value); break; - case RL_TEXTURE_FILTER_ANISOTROPIC: - { -#if !defined(GRAPHICS_API_OPENGL_11) - if (value <= RLGL.ExtSupported.maxAnisotropyLevel) glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_MAX_ANISOTROPY_EXT, (float)value); - else if (RLGL.ExtSupported.maxAnisotropyLevel > 0.0f) - { - TRACELOG(RL_LOG_WARNING, "GL: Maximum anisotropic filter level supported is %iX", id, (int)RLGL.ExtSupported.maxAnisotropyLevel); - glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_MAX_ANISOTROPY_EXT, (float)value); - } - else TRACELOG(RL_LOG_WARNING, "GL: Anisotropic filtering not supported"); -#endif - } break; -#if defined(GRAPHICS_API_OPENGL_33) - case RL_TEXTURE_MIPMAP_BIAS_RATIO: glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_LOD_BIAS, value/100.0f); -#endif - default: break; - } - - glBindTexture(GL_TEXTURE_2D, 0); -} - -// Set cubemap parameters (wrap mode/filter mode) -void rlCubemapParameters(unsigned int id, int param, int value) -{ -#if !defined(GRAPHICS_API_OPENGL_11) - glBindTexture(GL_TEXTURE_CUBE_MAP, id); - - // Reset anisotropy filter, in case it was set - glTexParameterf(GL_TEXTURE_CUBE_MAP, GL_TEXTURE_MAX_ANISOTROPY_EXT, 1.0f); - - switch (param) - { - case RL_TEXTURE_WRAP_S: - case RL_TEXTURE_WRAP_T: - { - if (value == RL_TEXTURE_WRAP_MIRROR_CLAMP) - { - if (RLGL.ExtSupported.texMirrorClamp) glTexParameteri(GL_TEXTURE_CUBE_MAP, param, value); - else TRACELOG(RL_LOG_WARNING, "GL: Clamp mirror wrap mode not supported (GL_MIRROR_CLAMP_EXT)"); - } - else glTexParameteri(GL_TEXTURE_CUBE_MAP, param, value); - - } break; - case RL_TEXTURE_MAG_FILTER: - case RL_TEXTURE_MIN_FILTER: glTexParameteri(GL_TEXTURE_CUBE_MAP, param, value); break; - case RL_TEXTURE_FILTER_ANISOTROPIC: - { - if (value <= RLGL.ExtSupported.maxAnisotropyLevel) glTexParameterf(GL_TEXTURE_CUBE_MAP, GL_TEXTURE_MAX_ANISOTROPY_EXT, (float)value); - else if (RLGL.ExtSupported.maxAnisotropyLevel > 0.0f) - { - TRACELOG(RL_LOG_WARNING, "GL: Maximum anisotropic filter level supported is %iX", id, (int)RLGL.ExtSupported.maxAnisotropyLevel); - glTexParameterf(GL_TEXTURE_CUBE_MAP, GL_TEXTURE_MAX_ANISOTROPY_EXT, (float)value); - } - else TRACELOG(RL_LOG_WARNING, "GL: Anisotropic filtering not supported"); - } break; -#if defined(GRAPHICS_API_OPENGL_33) - case RL_TEXTURE_MIPMAP_BIAS_RATIO: glTexParameterf(GL_TEXTURE_CUBE_MAP, GL_TEXTURE_LOD_BIAS, value/100.0f); -#endif - default: break; - } - - glBindTexture(GL_TEXTURE_CUBE_MAP, 0); -#endif -} - -// Enable shader program -void rlEnableShader(unsigned int id) -{ -#if (defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2)) - glUseProgram(id); -#endif -} - -// Disable shader program -void rlDisableShader(void) -{ -#if (defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2)) - glUseProgram(0); -#endif -} - -// Enable rendering to texture (fbo) -void rlEnableFramebuffer(unsigned int id) -{ -#if (defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2)) && defined(RLGL_RENDER_TEXTURES_HINT) - glBindFramebuffer(GL_FRAMEBUFFER, id); -#endif -} - -// return the active render texture (fbo) -unsigned int rlGetActiveFramebuffer(void) -{ - GLint fboId = 0; -#if (defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES3)) && defined(RLGL_RENDER_TEXTURES_HINT) - glGetIntegerv(GL_DRAW_FRAMEBUFFER_BINDING, &fboId); -#endif - return fboId; -} - -// Disable rendering to texture -void rlDisableFramebuffer(void) -{ -#if (defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2)) && defined(RLGL_RENDER_TEXTURES_HINT) - glBindFramebuffer(GL_FRAMEBUFFER, 0); -#endif -} - -// Blit active framebuffer to main framebuffer -void rlBlitFramebuffer(int srcX, int srcY, int srcWidth, int srcHeight, int dstX, int dstY, int dstWidth, int dstHeight, int bufferMask) -{ -#if (defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES3)) && defined(RLGL_RENDER_TEXTURES_HINT) - glBlitFramebuffer(srcX, srcY, srcWidth, srcHeight, dstX, dstY, dstWidth, dstHeight, bufferMask, GL_NEAREST); -#endif -} - -// Bind framebuffer object (fbo) -void rlBindFramebuffer(unsigned int target, unsigned int framebuffer) -{ -#if (defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2)) && defined(RLGL_RENDER_TEXTURES_HINT) - glBindFramebuffer(target, framebuffer); -#endif -} - -// Activate multiple draw color buffers -// NOTE: One color buffer is always active by default -void rlActiveDrawBuffers(int count) -{ -#if ((defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES3)) && defined(RLGL_RENDER_TEXTURES_HINT)) - // NOTE: Maximum number of draw buffers supported is implementation dependant, - // it can be queried with glGet*() but it must be at least 8 - //GLint maxDrawBuffers = 0; - //glGetIntegerv(GL_MAX_DRAW_BUFFERS, &maxDrawBuffers); - - if (count > 0) - { - if (count > 8) TRACELOG(LOG_WARNING, "GL: Max color buffers limited to 8"); - else - { - unsigned int buffers[8] = { -#if defined(GRAPHICS_API_OPENGL_ES3) - GL_COLOR_ATTACHMENT0_EXT, - GL_COLOR_ATTACHMENT1_EXT, - GL_COLOR_ATTACHMENT2_EXT, - GL_COLOR_ATTACHMENT3_EXT, - GL_COLOR_ATTACHMENT4_EXT, - GL_COLOR_ATTACHMENT5_EXT, - GL_COLOR_ATTACHMENT6_EXT, - GL_COLOR_ATTACHMENT7_EXT, -#else - GL_COLOR_ATTACHMENT0, - GL_COLOR_ATTACHMENT1, - GL_COLOR_ATTACHMENT2, - GL_COLOR_ATTACHMENT3, - GL_COLOR_ATTACHMENT4, - GL_COLOR_ATTACHMENT5, - GL_COLOR_ATTACHMENT6, - GL_COLOR_ATTACHMENT7, -#endif - }; - -#if defined(GRAPHICS_API_OPENGL_ES3) - glDrawBuffersEXT(count, buffers); -#else - glDrawBuffers(count, buffers); -#endif - } - } - else TRACELOG(LOG_WARNING, "GL: One color buffer active by default"); -#endif -} - -//---------------------------------------------------------------------------------- -// General render state configuration -//---------------------------------------------------------------------------------- - -// Enable color blending -void rlEnableColorBlend(void) { glEnable(GL_BLEND); } - -// Disable color blending -void rlDisableColorBlend(void) { glDisable(GL_BLEND); } - -// Enable depth test -void rlEnableDepthTest(void) { glEnable(GL_DEPTH_TEST); } - -// Disable depth test -void rlDisableDepthTest(void) { glDisable(GL_DEPTH_TEST); } - -// Enable depth write -void rlEnableDepthMask(void) { glDepthMask(GL_TRUE); } - -// Disable depth write -void rlDisableDepthMask(void) { glDepthMask(GL_FALSE); } - -// Enable backface culling -void rlEnableBackfaceCulling(void) { glEnable(GL_CULL_FACE); } - -// Disable backface culling -void rlDisableBackfaceCulling(void) { glDisable(GL_CULL_FACE); } - -// Set color mask active for screen read/draw -void rlColorMask(bool r, bool g, bool b, bool a) { glColorMask(r, g, b, a); } - -// Set face culling mode -void rlSetCullFace(int mode) -{ - switch (mode) - { - case RL_CULL_FACE_BACK: glCullFace(GL_BACK); break; - case RL_CULL_FACE_FRONT: glCullFace(GL_FRONT); break; - default: break; - } -} - -// Enable scissor test -void rlEnableScissorTest(void) { glEnable(GL_SCISSOR_TEST); } - -// Disable scissor test -void rlDisableScissorTest(void) { glDisable(GL_SCISSOR_TEST); } - -// Scissor test -void rlScissor(int x, int y, int width, int height) { glScissor(x, y, width, height); } - -// Enable wire mode -void rlEnableWireMode(void) -{ -#if defined(GRAPHICS_API_OPENGL_11) || defined(GRAPHICS_API_OPENGL_33) - // NOTE: glPolygonMode() not available on OpenGL ES - glPolygonMode(GL_FRONT_AND_BACK, GL_LINE); -#endif -} - -// Enable point mode -void rlEnablePointMode(void) -{ -#if defined(GRAPHICS_API_OPENGL_11) || defined(GRAPHICS_API_OPENGL_33) - // NOTE: glPolygonMode() not available on OpenGL ES - glPolygonMode(GL_FRONT_AND_BACK, GL_POINT); - glEnable(GL_PROGRAM_POINT_SIZE); -#endif -} - -// Disable wire mode -void rlDisableWireMode(void) -{ -#if defined(GRAPHICS_API_OPENGL_11) || defined(GRAPHICS_API_OPENGL_33) - // NOTE: glPolygonMode() not available on OpenGL ES - glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); -#endif -} - -// Set the line drawing width -void rlSetLineWidth(float width) { glLineWidth(width); } - -// Get the line drawing width -float rlGetLineWidth(void) -{ - float width = 0; - glGetFloatv(GL_LINE_WIDTH, &width); - return width; -} - -// Enable line aliasing -void rlEnableSmoothLines(void) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_11) - glEnable(GL_LINE_SMOOTH); -#endif -} - -// Disable line aliasing -void rlDisableSmoothLines(void) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_11) - glDisable(GL_LINE_SMOOTH); -#endif -} - -// Enable stereo rendering -void rlEnableStereoRender(void) -{ -#if (defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2)) - RLGL.State.stereoRender = true; -#endif -} - -// Disable stereo rendering -void rlDisableStereoRender(void) -{ -#if (defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2)) - RLGL.State.stereoRender = false; -#endif -} - -// Check if stereo render is enabled -bool rlIsStereoRenderEnabled(void) -{ -#if (defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2)) - return RLGL.State.stereoRender; -#else - return false; -#endif -} - -// Clear color buffer with color -void rlClearColor(unsigned char r, unsigned char g, unsigned char b, unsigned char a) -{ - // Color values clamp to 0.0f(0) and 1.0f(255) - float cr = (float)r/255; - float cg = (float)g/255; - float cb = (float)b/255; - float ca = (float)a/255; - - glClearColor(cr, cg, cb, ca); -} - -// Clear used screen buffers (color and depth) -void rlClearScreenBuffers(void) -{ - glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); // Clear used buffers: Color and Depth (Depth is used for 3D) - //glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT | GL_STENCIL_BUFFER_BIT); // Stencil buffer not used... -} - -// Check and log OpenGL error codes -void rlCheckErrors(void) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - int check = 1; - while (check) - { - const GLenum err = glGetError(); - switch (err) - { - case GL_NO_ERROR: check = 0; break; - case 0x0500: TRACELOG(RL_LOG_WARNING, "GL: Error detected: GL_INVALID_ENUM"); break; - case 0x0501: TRACELOG(RL_LOG_WARNING, "GL: Error detected: GL_INVALID_VALUE"); break; - case 0x0502: TRACELOG(RL_LOG_WARNING, "GL: Error detected: GL_INVALID_OPERATION"); break; - case 0x0503: TRACELOG(RL_LOG_WARNING, "GL: Error detected: GL_STACK_OVERFLOW"); break; - case 0x0504: TRACELOG(RL_LOG_WARNING, "GL: Error detected: GL_STACK_UNDERFLOW"); break; - case 0x0505: TRACELOG(RL_LOG_WARNING, "GL: Error detected: GL_OUT_OF_MEMORY"); break; - case 0x0506: TRACELOG(RL_LOG_WARNING, "GL: Error detected: GL_INVALID_FRAMEBUFFER_OPERATION"); break; - default: TRACELOG(RL_LOG_WARNING, "GL: Error detected: Unknown error code: %x", err); break; - } - } -#endif -} - -// Set blend mode -void rlSetBlendMode(int mode) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - if ((RLGL.State.currentBlendMode != mode) || ((mode == RL_BLEND_CUSTOM || mode == RL_BLEND_CUSTOM_SEPARATE) && RLGL.State.glCustomBlendModeModified)) - { - rlDrawRenderBatch(RLGL.currentBatch); - - switch (mode) - { - case RL_BLEND_ALPHA: glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); glBlendEquation(GL_FUNC_ADD); break; - case RL_BLEND_ADDITIVE: glBlendFunc(GL_SRC_ALPHA, GL_ONE); glBlendEquation(GL_FUNC_ADD); break; - case RL_BLEND_MULTIPLIED: glBlendFunc(GL_DST_COLOR, GL_ONE_MINUS_SRC_ALPHA); glBlendEquation(GL_FUNC_ADD); break; - case RL_BLEND_ADD_COLORS: glBlendFunc(GL_ONE, GL_ONE); glBlendEquation(GL_FUNC_ADD); break; - case RL_BLEND_SUBTRACT_COLORS: glBlendFunc(GL_ONE, GL_ONE); glBlendEquation(GL_FUNC_SUBTRACT); break; - case RL_BLEND_ALPHA_PREMULTIPLY: glBlendFunc(GL_ONE, GL_ONE_MINUS_SRC_ALPHA); glBlendEquation(GL_FUNC_ADD); break; - case RL_BLEND_CUSTOM: - { - // NOTE: Using GL blend src/dst factors and GL equation configured with rlSetBlendFactors() - glBlendFunc(RLGL.State.glBlendSrcFactor, RLGL.State.glBlendDstFactor); glBlendEquation(RLGL.State.glBlendEquation); - - } break; - case RL_BLEND_CUSTOM_SEPARATE: - { - // NOTE: Using GL blend src/dst factors and GL equation configured with rlSetBlendFactorsSeparate() - glBlendFuncSeparate(RLGL.State.glBlendSrcFactorRGB, RLGL.State.glBlendDestFactorRGB, RLGL.State.glBlendSrcFactorAlpha, RLGL.State.glBlendDestFactorAlpha); - glBlendEquationSeparate(RLGL.State.glBlendEquationRGB, RLGL.State.glBlendEquationAlpha); - - } break; - default: break; - } - - RLGL.State.currentBlendMode = mode; - RLGL.State.glCustomBlendModeModified = false; - } -#endif -} - -// Set blending mode factor and equation -void rlSetBlendFactors(int glSrcFactor, int glDstFactor, int glEquation) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - if ((RLGL.State.glBlendSrcFactor != glSrcFactor) || - (RLGL.State.glBlendDstFactor != glDstFactor) || - (RLGL.State.glBlendEquation != glEquation)) - { - RLGL.State.glBlendSrcFactor = glSrcFactor; - RLGL.State.glBlendDstFactor = glDstFactor; - RLGL.State.glBlendEquation = glEquation; - - RLGL.State.glCustomBlendModeModified = true; - } -#endif -} - -// Set blending mode factor and equation separately for RGB and alpha -void rlSetBlendFactorsSeparate(int glSrcRGB, int glDstRGB, int glSrcAlpha, int glDstAlpha, int glEqRGB, int glEqAlpha) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - if ((RLGL.State.glBlendSrcFactorRGB != glSrcRGB) || - (RLGL.State.glBlendDestFactorRGB != glDstRGB) || - (RLGL.State.glBlendSrcFactorAlpha != glSrcAlpha) || - (RLGL.State.glBlendDestFactorAlpha != glDstAlpha) || - (RLGL.State.glBlendEquationRGB != glEqRGB) || - (RLGL.State.glBlendEquationAlpha != glEqAlpha)) - { - RLGL.State.glBlendSrcFactorRGB = glSrcRGB; - RLGL.State.glBlendDestFactorRGB = glDstRGB; - RLGL.State.glBlendSrcFactorAlpha = glSrcAlpha; - RLGL.State.glBlendDestFactorAlpha = glDstAlpha; - RLGL.State.glBlendEquationRGB = glEqRGB; - RLGL.State.glBlendEquationAlpha = glEqAlpha; - - RLGL.State.glCustomBlendModeModified = true; - } -#endif -} - -//---------------------------------------------------------------------------------- -// Module Functions Definition - OpenGL Debug -//---------------------------------------------------------------------------------- -#if defined(RLGL_ENABLE_OPENGL_DEBUG_CONTEXT) && defined(GRAPHICS_API_OPENGL_43) -static void GLAPIENTRY rlDebugMessageCallback(GLenum source, GLenum type, GLuint id, GLenum severity, GLsizei length, const GLchar *message, const void *userParam) -{ - // Ignore non-significant error/warning codes (NVidia drivers) - // NOTE: Here there are the details with a sample output: - // - #131169 - Framebuffer detailed info: The driver allocated storage for renderbuffer 2. (severity: low) - // - #131185 - Buffer detailed info: Buffer object 1 (bound to GL_ELEMENT_ARRAY_BUFFER_ARB, usage hint is GL_ENUM_88e4) - // will use VIDEO memory as the source for buffer object operations. (severity: low) - // - #131218 - Program/shader state performance warning: Vertex shader in program 7 is being recompiled based on GL state. (severity: medium) - // - #131204 - Texture state usage warning: The texture object (0) bound to texture image unit 0 does not have - // a defined base level and cannot be used for texture mapping. (severity: low) - if ((id == 131169) || (id == 131185) || (id == 131218) || (id == 131204)) return; - - const char *msgSource = NULL; - switch (source) - { - case GL_DEBUG_SOURCE_API: msgSource = "API"; break; - case GL_DEBUG_SOURCE_WINDOW_SYSTEM: msgSource = "WINDOW_SYSTEM"; break; - case GL_DEBUG_SOURCE_SHADER_COMPILER: msgSource = "SHADER_COMPILER"; break; - case GL_DEBUG_SOURCE_THIRD_PARTY: msgSource = "THIRD_PARTY"; break; - case GL_DEBUG_SOURCE_APPLICATION: msgSource = "APPLICATION"; break; - case GL_DEBUG_SOURCE_OTHER: msgSource = "OTHER"; break; - default: break; - } - - const char *msgType = NULL; - switch (type) - { - case GL_DEBUG_TYPE_ERROR: msgType = "ERROR"; break; - case GL_DEBUG_TYPE_DEPRECATED_BEHAVIOR: msgType = "DEPRECATED_BEHAVIOR"; break; - case GL_DEBUG_TYPE_UNDEFINED_BEHAVIOR: msgType = "UNDEFINED_BEHAVIOR"; break; - case GL_DEBUG_TYPE_PORTABILITY: msgType = "PORTABILITY"; break; - case GL_DEBUG_TYPE_PERFORMANCE: msgType = "PERFORMANCE"; break; - case GL_DEBUG_TYPE_MARKER: msgType = "MARKER"; break; - case GL_DEBUG_TYPE_PUSH_GROUP: msgType = "PUSH_GROUP"; break; - case GL_DEBUG_TYPE_POP_GROUP: msgType = "POP_GROUP"; break; - case GL_DEBUG_TYPE_OTHER: msgType = "OTHER"; break; - default: break; - } - - const char *msgSeverity = "DEFAULT"; - switch (severity) - { - case GL_DEBUG_SEVERITY_LOW: msgSeverity = "LOW"; break; - case GL_DEBUG_SEVERITY_MEDIUM: msgSeverity = "MEDIUM"; break; - case GL_DEBUG_SEVERITY_HIGH: msgSeverity = "HIGH"; break; - case GL_DEBUG_SEVERITY_NOTIFICATION: msgSeverity = "NOTIFICATION"; break; - default: break; - } - - TRACELOG(LOG_WARNING, "GL: OpenGL debug message: %s", message); - TRACELOG(LOG_WARNING, " > Type: %s", msgType); - TRACELOG(LOG_WARNING, " > Source = %s", msgSource); - TRACELOG(LOG_WARNING, " > Severity = %s", msgSeverity); -} -#endif - -//---------------------------------------------------------------------------------- -// Module Functions Definition - rlgl functionality -//---------------------------------------------------------------------------------- - -// Initialize rlgl: OpenGL extensions, default buffers/shaders/textures, OpenGL states -void rlglInit(int width, int height) -{ - // Enable OpenGL debug context if required -#if defined(RLGL_ENABLE_OPENGL_DEBUG_CONTEXT) && defined(GRAPHICS_API_OPENGL_43) - if ((glDebugMessageCallback != NULL) && (glDebugMessageControl != NULL)) - { - glDebugMessageCallback(rlDebugMessageCallback, 0); - // glDebugMessageControl(GL_DEBUG_SOURCE_API, GL_DEBUG_TYPE_ERROR, GL_DEBUG_SEVERITY_HIGH, 0, 0, GL_TRUE); - - // Debug context options: - // - GL_DEBUG_OUTPUT - Faster version but not useful for breakpoints - // - GL_DEBUG_OUTPUT_SYNCHRONUS - Callback is in sync with errors, so a breakpoint can be placed on the callback in order to get a stacktrace for the GL error - glEnable(GL_DEBUG_OUTPUT); - glEnable(GL_DEBUG_OUTPUT_SYNCHRONOUS); - } -#endif - -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - // Init default white texture - unsigned char pixels[4] = { 255, 255, 255, 255 }; // 1 pixel RGBA (4 bytes) - RLGL.State.defaultTextureId = rlLoadTexture(pixels, 1, 1, RL_PIXELFORMAT_UNCOMPRESSED_R8G8B8A8, 1); - - if (RLGL.State.defaultTextureId != 0) TRACELOG(RL_LOG_INFO, "TEXTURE: [ID %i] Default texture loaded successfully", RLGL.State.defaultTextureId); - else TRACELOG(RL_LOG_WARNING, "TEXTURE: Failed to load default texture"); - - // Init default Shader (customized for GL 3.3 and ES2) - // Loaded: RLGL.State.defaultShaderId + RLGL.State.defaultShaderLocs - rlLoadShaderDefault(); - RLGL.State.currentShaderId = RLGL.State.defaultShaderId; - RLGL.State.currentShaderLocs = RLGL.State.defaultShaderLocs; - - // Init default vertex arrays buffers - // Simulate that the default shader has the location RL_SHADER_LOC_VERTEX_NORMAL to bind the normal buffer for the default render batch - RLGL.State.currentShaderLocs[RL_SHADER_LOC_VERTEX_NORMAL] = RL_DEFAULT_SHADER_ATTRIB_LOCATION_NORMAL; - RLGL.defaultBatch = rlLoadRenderBatch(RL_DEFAULT_BATCH_BUFFERS, RL_DEFAULT_BATCH_BUFFER_ELEMENTS); - RLGL.State.currentShaderLocs[RL_SHADER_LOC_VERTEX_NORMAL] = -1; - RLGL.currentBatch = &RLGL.defaultBatch; - - // Init stack matrices (emulating OpenGL 1.1) - for (int i = 0; i < RL_MAX_MATRIX_STACK_SIZE; i++) RLGL.State.stack[i] = rlMatrixIdentity(); - - // Init internal matrices - RLGL.State.transform = rlMatrixIdentity(); - RLGL.State.projection = rlMatrixIdentity(); - RLGL.State.modelview = rlMatrixIdentity(); - RLGL.State.currentMatrix = &RLGL.State.modelview; -#endif // GRAPHICS_API_OPENGL_33 || GRAPHICS_API_OPENGL_ES2 - - // Initialize OpenGL default states - //---------------------------------------------------------- - // Init state: Depth test - glDepthFunc(GL_LEQUAL); // Type of depth testing to apply - glDisable(GL_DEPTH_TEST); // Disable depth testing for 2D (only used for 3D) - - // Init state: Blending mode - glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); // Color blending function (how colors are mixed) - glEnable(GL_BLEND); // Enable color blending (required to work with transparencies) - - // Init state: Culling - // NOTE: All shapes/models triangles are drawn CCW - glCullFace(GL_BACK); // Cull the back face (default) - glFrontFace(GL_CCW); // Front face are defined counter clockwise (default) - glEnable(GL_CULL_FACE); // Enable backface culling - - // Init state: Cubemap seamless -#if defined(GRAPHICS_API_OPENGL_33) - glEnable(GL_TEXTURE_CUBE_MAP_SEAMLESS); // Seamless cubemaps (not supported on OpenGL ES 2.0) -#endif - -#if defined(GRAPHICS_API_OPENGL_11) - // Init state: Color hints (deprecated in OpenGL 3.0+) - glHint(GL_PERSPECTIVE_CORRECTION_HINT, GL_NICEST); // Improve quality of color and texture coordinate interpolation - glShadeModel(GL_SMOOTH); // Smooth shading between vertex (vertex colors interpolation) -#endif - -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - // Store screen size into global variables - RLGL.State.framebufferWidth = width; - RLGL.State.framebufferHeight = height; - - TRACELOG(RL_LOG_INFO, "RLGL: Default OpenGL state initialized successfully"); - //---------------------------------------------------------- -#endif - - // Init state: Color/Depth buffers clear - glClearColor(0.0f, 0.0f, 0.0f, 1.0f); // Set clear color (black) - glClearDepth(1.0f); // Set clear depth value (default) - glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); // Clear color and depth buffers (depth buffer required for 3D) -} - -// Vertex Buffer Object deinitialization (memory free) -void rlglClose(void) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - rlUnloadRenderBatch(RLGL.defaultBatch); - - rlUnloadShaderDefault(); // Unload default shader - - glDeleteTextures(1, &RLGL.State.defaultTextureId); // Unload default texture - TRACELOG(RL_LOG_INFO, "TEXTURE: [ID %i] Default texture unloaded successfully", RLGL.State.defaultTextureId); -#endif -} - -// Load OpenGL extensions -// NOTE: External loader function must be provided -void rlLoadExtensions(void *loader) -{ -#if defined(GRAPHICS_API_OPENGL_33) // Also defined for GRAPHICS_API_OPENGL_21 - // NOTE: glad is generated and contains only required OpenGL 3.3 Core extensions (and lower versions) - if (gladLoadGL((GLADloadfunc)loader) == 0) TRACELOG(RL_LOG_WARNING, "GLAD: Cannot load OpenGL extensions"); - else TRACELOG(RL_LOG_INFO, "GLAD: OpenGL extensions loaded successfully"); - - // Get number of supported extensions - GLint numExt = 0; - glGetIntegerv(GL_NUM_EXTENSIONS, &numExt); - TRACELOG(RL_LOG_INFO, "GL: Supported extensions count: %i", numExt); - -#if defined(RLGL_SHOW_GL_DETAILS_INFO) - // Get supported extensions list - // WARNING: glGetStringi() not available on OpenGL 2.1 - TRACELOG(RL_LOG_INFO, "GL: OpenGL extensions:"); - for (int i = 0; i < numExt; i++) TRACELOG(RL_LOG_INFO, " %s", glGetStringi(GL_EXTENSIONS, i)); -#endif - -#if defined(GRAPHICS_API_OPENGL_21) - // Register supported extensions flags - // Optional OpenGL 2.1 extensions - RLGL.ExtSupported.vao = GLAD_GL_ARB_vertex_array_object; - RLGL.ExtSupported.instancing = (GLAD_GL_EXT_draw_instanced && GLAD_GL_ARB_instanced_arrays); - RLGL.ExtSupported.texNPOT = GLAD_GL_ARB_texture_non_power_of_two; - RLGL.ExtSupported.texFloat32 = GLAD_GL_ARB_texture_float; - RLGL.ExtSupported.texFloat16 = GLAD_GL_ARB_texture_float; - RLGL.ExtSupported.texDepth = GLAD_GL_ARB_depth_texture; - RLGL.ExtSupported.maxDepthBits = 32; - RLGL.ExtSupported.texAnisoFilter = GLAD_GL_EXT_texture_filter_anisotropic; - RLGL.ExtSupported.texMirrorClamp = GLAD_GL_EXT_texture_mirror_clamp; -#else - // Register supported extensions flags - // OpenGL 3.3 extensions supported by default (core) - RLGL.ExtSupported.vao = true; - RLGL.ExtSupported.instancing = true; - RLGL.ExtSupported.texNPOT = true; - RLGL.ExtSupported.texFloat32 = true; - RLGL.ExtSupported.texFloat16 = true; - RLGL.ExtSupported.texDepth = true; - RLGL.ExtSupported.maxDepthBits = 32; - RLGL.ExtSupported.texAnisoFilter = true; - RLGL.ExtSupported.texMirrorClamp = true; -#endif - - // Optional OpenGL 3.3 extensions - RLGL.ExtSupported.texCompASTC = GLAD_GL_KHR_texture_compression_astc_hdr && GLAD_GL_KHR_texture_compression_astc_ldr; - RLGL.ExtSupported.texCompDXT = GLAD_GL_EXT_texture_compression_s3tc; // Texture compression: DXT - RLGL.ExtSupported.texCompETC2 = GLAD_GL_ARB_ES3_compatibility; // Texture compression: ETC2/EAC - #if defined(GRAPHICS_API_OPENGL_43) - RLGL.ExtSupported.computeShader = GLAD_GL_ARB_compute_shader; - RLGL.ExtSupported.ssbo = GLAD_GL_ARB_shader_storage_buffer_object; - #endif - -#endif // GRAPHICS_API_OPENGL_33 - -#if defined(GRAPHICS_API_OPENGL_ES3) - // Register supported extensions flags - // OpenGL ES 3.0 extensions supported by default (or it should be) - RLGL.ExtSupported.vao = true; - RLGL.ExtSupported.instancing = true; - RLGL.ExtSupported.texNPOT = true; - RLGL.ExtSupported.texFloat32 = true; - RLGL.ExtSupported.texFloat16 = true; - RLGL.ExtSupported.texDepth = true; - RLGL.ExtSupported.texDepthWebGL = true; - RLGL.ExtSupported.maxDepthBits = 24; - RLGL.ExtSupported.texAnisoFilter = true; - RLGL.ExtSupported.texMirrorClamp = true; - // TODO: Check for additional OpenGL ES 3.0 supported extensions: - //RLGL.ExtSupported.texCompDXT = true; - //RLGL.ExtSupported.texCompETC1 = true; - //RLGL.ExtSupported.texCompETC2 = true; - //RLGL.ExtSupported.texCompPVRT = true; - //RLGL.ExtSupported.texCompASTC = true; - //RLGL.ExtSupported.maxAnisotropyLevel = true; - //RLGL.ExtSupported.computeShader = true; - //RLGL.ExtSupported.ssbo = true; - -#elif defined(GRAPHICS_API_OPENGL_ES2) - - #if defined(PLATFORM_DESKTOP_GLFW) || defined(PLATFORM_DESKTOP_SDL) - // TODO: Support GLAD loader for OpenGL ES 3.0 - if (gladLoadGLES2((GLADloadfunc)loader) == 0) TRACELOG(RL_LOG_WARNING, "GLAD: Cannot load OpenGL ES2.0 functions"); - else TRACELOG(RL_LOG_INFO, "GLAD: OpenGL ES 2.0 loaded successfully"); - #endif - - // Get supported extensions list - GLint numExt = 0; - const char **extList = RL_MALLOC(512*sizeof(const char *)); // Allocate 512 strings pointers (2 KB) - const char *extensions = (const char *)glGetString(GL_EXTENSIONS); // One big const string - - // NOTE: We have to duplicate string because glGetString() returns a const string - int size = strlen(extensions) + 1; // Get extensions string size in bytes - char *extensionsDup = (char *)RL_CALLOC(size, sizeof(char)); - strcpy(extensionsDup, extensions); - extList[numExt] = extensionsDup; - - for (int i = 0; i < size; i++) - { - if (extensionsDup[i] == ' ') - { - extensionsDup[i] = '\0'; - numExt++; - extList[numExt] = &extensionsDup[i + 1]; - } - } - - TRACELOG(RL_LOG_INFO, "GL: Supported extensions count: %i", numExt); - -#if defined(RLGL_SHOW_GL_DETAILS_INFO) - TRACELOG(RL_LOG_INFO, "GL: OpenGL extensions:"); - for (int i = 0; i < numExt; i++) TRACELOG(RL_LOG_INFO, " %s", extList[i]); -#endif - - // Check required extensions - for (int i = 0; i < numExt; i++) - { - // Check VAO support - // NOTE: Only check on OpenGL ES, OpenGL 3.3 has VAO support as core feature - if (strcmp(extList[i], (const char *)"GL_OES_vertex_array_object") == 0) - { - // The extension is supported by our hardware and driver, try to get related functions pointers - // NOTE: emscripten does not support VAOs natively, it uses emulation and it reduces overall performance... - glGenVertexArrays = (PFNGLGENVERTEXARRAYSOESPROC)((rlglLoadProc)loader)("glGenVertexArraysOES"); - glBindVertexArray = (PFNGLBINDVERTEXARRAYOESPROC)((rlglLoadProc)loader)("glBindVertexArrayOES"); - glDeleteVertexArrays = (PFNGLDELETEVERTEXARRAYSOESPROC)((rlglLoadProc)loader)("glDeleteVertexArraysOES"); - //glIsVertexArray = (PFNGLISVERTEXARRAYOESPROC)loader("glIsVertexArrayOES"); // NOTE: Fails in WebGL, omitted - - if ((glGenVertexArrays != NULL) && (glBindVertexArray != NULL) && (glDeleteVertexArrays != NULL)) RLGL.ExtSupported.vao = true; - } - - // Check instanced rendering support - if (strstr(extList[i], (const char*)"instanced_arrays") != NULL) // Broad check for instanced_arrays - { - // Specific check - if (strcmp(extList[i], (const char *)"GL_ANGLE_instanced_arrays") == 0) // ANGLE - { - glDrawArraysInstanced = (PFNGLDRAWARRAYSINSTANCEDEXTPROC)((rlglLoadProc)loader)("glDrawArraysInstancedANGLE"); - glDrawElementsInstanced = (PFNGLDRAWELEMENTSINSTANCEDEXTPROC)((rlglLoadProc)loader)("glDrawElementsInstancedANGLE"); - glVertexAttribDivisor = (PFNGLVERTEXATTRIBDIVISOREXTPROC)((rlglLoadProc)loader)("glVertexAttribDivisorANGLE"); - } - else if (strcmp(extList[i], (const char *)"GL_EXT_instanced_arrays") == 0) // EXT - { - glDrawArraysInstanced = (PFNGLDRAWARRAYSINSTANCEDEXTPROC)((rlglLoadProc)loader)("glDrawArraysInstancedEXT"); - glDrawElementsInstanced = (PFNGLDRAWELEMENTSINSTANCEDEXTPROC)((rlglLoadProc)loader)("glDrawElementsInstancedEXT"); - glVertexAttribDivisor = (PFNGLVERTEXATTRIBDIVISOREXTPROC)((rlglLoadProc)loader)("glVertexAttribDivisorEXT"); - } - else if (strcmp(extList[i], (const char *)"GL_NV_instanced_arrays") == 0) // NVIDIA GLES - { - glDrawArraysInstanced = (PFNGLDRAWARRAYSINSTANCEDEXTPROC)((rlglLoadProc)loader)("glDrawArraysInstancedNV"); - glDrawElementsInstanced = (PFNGLDRAWELEMENTSINSTANCEDEXTPROC)((rlglLoadProc)loader)("glDrawElementsInstancedNV"); - glVertexAttribDivisor = (PFNGLVERTEXATTRIBDIVISOREXTPROC)((rlglLoadProc)loader)("glVertexAttribDivisorNV"); - } - - // The feature will only be marked as supported if the elements from GL_XXX_instanced_arrays are present - if ((glDrawArraysInstanced != NULL) && (glDrawElementsInstanced != NULL) && (glVertexAttribDivisor != NULL)) RLGL.ExtSupported.instancing = true; - } - else if (strstr(extList[i], (const char *)"draw_instanced") != NULL) - { - // GL_ANGLE_draw_instanced doesn't exist - if (strcmp(extList[i], (const char *)"GL_EXT_draw_instanced") == 0) - { - glDrawArraysInstanced = (PFNGLDRAWARRAYSINSTANCEDEXTPROC)((rlglLoadProc)loader)("glDrawArraysInstancedEXT"); - glDrawElementsInstanced = (PFNGLDRAWELEMENTSINSTANCEDEXTPROC)((rlglLoadProc)loader)("glDrawElementsInstancedEXT"); - } - else if (strcmp(extList[i], (const char*)"GL_NV_draw_instanced") == 0) - { - glDrawArraysInstanced = (PFNGLDRAWARRAYSINSTANCEDEXTPROC)((rlglLoadProc)loader)("glDrawArraysInstancedNV"); - glDrawElementsInstanced = (PFNGLDRAWELEMENTSINSTANCEDEXTPROC)((rlglLoadProc)loader)("glDrawElementsInstancedNV"); - } - - // But the functions will at least be loaded if only GL_XX_EXT_draw_instanced exist - if ((glDrawArraysInstanced != NULL) && (glDrawElementsInstanced != NULL) && (glVertexAttribDivisor != NULL)) RLGL.ExtSupported.instancing = true; - } - - // Check NPOT textures support - // NOTE: Only check on OpenGL ES, OpenGL 3.3 has NPOT textures full support as core feature - if (strcmp(extList[i], (const char *)"GL_OES_texture_npot") == 0) RLGL.ExtSupported.texNPOT = true; - - // Check texture float support - if (strcmp(extList[i], (const char *)"GL_OES_texture_float") == 0) RLGL.ExtSupported.texFloat32 = true; - if (strcmp(extList[i], (const char *)"GL_OES_texture_half_float") == 0) RLGL.ExtSupported.texFloat16 = true; - - // Check depth texture support - if (strcmp(extList[i], (const char *)"GL_OES_depth_texture") == 0) RLGL.ExtSupported.texDepth = true; - if (strcmp(extList[i], (const char *)"GL_WEBGL_depth_texture") == 0) RLGL.ExtSupported.texDepthWebGL = true; // WebGL requires unsized internal format - if (RLGL.ExtSupported.texDepthWebGL) RLGL.ExtSupported.texDepth = true; - - if (strcmp(extList[i], (const char *)"GL_OES_depth24") == 0) RLGL.ExtSupported.maxDepthBits = 24; // Not available on WebGL - if (strcmp(extList[i], (const char *)"GL_OES_depth32") == 0) RLGL.ExtSupported.maxDepthBits = 32; // Not available on WebGL - - // Check texture compression support: DXT - if ((strcmp(extList[i], (const char *)"GL_EXT_texture_compression_s3tc") == 0) || - (strcmp(extList[i], (const char *)"GL_WEBGL_compressed_texture_s3tc") == 0) || - (strcmp(extList[i], (const char *)"GL_WEBKIT_WEBGL_compressed_texture_s3tc") == 0)) RLGL.ExtSupported.texCompDXT = true; - - // Check texture compression support: ETC1 - if ((strcmp(extList[i], (const char *)"GL_OES_compressed_ETC1_RGB8_texture") == 0) || - (strcmp(extList[i], (const char *)"GL_WEBGL_compressed_texture_etc1") == 0)) RLGL.ExtSupported.texCompETC1 = true; - - // Check texture compression support: ETC2/EAC - if (strcmp(extList[i], (const char *)"GL_ARB_ES3_compatibility") == 0) RLGL.ExtSupported.texCompETC2 = true; - - // Check texture compression support: PVR - if (strcmp(extList[i], (const char *)"GL_IMG_texture_compression_pvrtc") == 0) RLGL.ExtSupported.texCompPVRT = true; - - // Check texture compression support: ASTC - if (strcmp(extList[i], (const char *)"GL_KHR_texture_compression_astc_hdr") == 0) RLGL.ExtSupported.texCompASTC = true; - - // Check anisotropic texture filter support - if (strcmp(extList[i], (const char *)"GL_EXT_texture_filter_anisotropic") == 0) RLGL.ExtSupported.texAnisoFilter = true; - - // Check clamp mirror wrap mode support - if (strcmp(extList[i], (const char *)"GL_EXT_texture_mirror_clamp") == 0) RLGL.ExtSupported.texMirrorClamp = true; - } - - // Free extensions pointers - RL_FREE(extList); - RL_FREE(extensionsDup); // Duplicated string must be deallocated -#endif // GRAPHICS_API_OPENGL_ES2 - - // Check OpenGL information and capabilities - //------------------------------------------------------------------------------ - // Show current OpenGL and GLSL version - TRACELOG(RL_LOG_INFO, "GL: OpenGL device information:"); - TRACELOG(RL_LOG_INFO, " > Vendor: %s", glGetString(GL_VENDOR)); - TRACELOG(RL_LOG_INFO, " > Renderer: %s", glGetString(GL_RENDERER)); - TRACELOG(RL_LOG_INFO, " > Version: %s", glGetString(GL_VERSION)); - TRACELOG(RL_LOG_INFO, " > GLSL: %s", glGetString(GL_SHADING_LANGUAGE_VERSION)); - -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - // NOTE: Anisotropy levels capability is an extension - #ifndef GL_MAX_TEXTURE_MAX_ANISOTROPY_EXT - #define GL_MAX_TEXTURE_MAX_ANISOTROPY_EXT 0x84FF - #endif - glGetFloatv(GL_MAX_TEXTURE_MAX_ANISOTROPY_EXT, &RLGL.ExtSupported.maxAnisotropyLevel); - -#if defined(RLGL_SHOW_GL_DETAILS_INFO) - // Show some OpenGL GPU capabilities - TRACELOG(RL_LOG_INFO, "GL: OpenGL capabilities:"); - GLint capability = 0; - glGetIntegerv(GL_MAX_TEXTURE_SIZE, &capability); - TRACELOG(RL_LOG_INFO, " GL_MAX_TEXTURE_SIZE: %i", capability); - glGetIntegerv(GL_MAX_CUBE_MAP_TEXTURE_SIZE, &capability); - TRACELOG(RL_LOG_INFO, " GL_MAX_CUBE_MAP_TEXTURE_SIZE: %i", capability); - glGetIntegerv(GL_MAX_TEXTURE_IMAGE_UNITS, &capability); - TRACELOG(RL_LOG_INFO, " GL_MAX_TEXTURE_IMAGE_UNITS: %i", capability); - glGetIntegerv(GL_MAX_VERTEX_ATTRIBS, &capability); - TRACELOG(RL_LOG_INFO, " GL_MAX_VERTEX_ATTRIBS: %i", capability); - #if !defined(GRAPHICS_API_OPENGL_ES2) - glGetIntegerv(GL_MAX_UNIFORM_BLOCK_SIZE, &capability); - TRACELOG(RL_LOG_INFO, " GL_MAX_UNIFORM_BLOCK_SIZE: %i", capability); - glGetIntegerv(GL_MAX_DRAW_BUFFERS, &capability); - TRACELOG(RL_LOG_INFO, " GL_MAX_DRAW_BUFFERS: %i", capability); - if (RLGL.ExtSupported.texAnisoFilter) TRACELOG(RL_LOG_INFO, " GL_MAX_TEXTURE_MAX_ANISOTROPY: %.0f", RLGL.ExtSupported.maxAnisotropyLevel); - #endif - glGetIntegerv(GL_NUM_COMPRESSED_TEXTURE_FORMATS, &capability); - TRACELOG(RL_LOG_INFO, " GL_NUM_COMPRESSED_TEXTURE_FORMATS: %i", capability); - GLint *compFormats = (GLint *)RL_CALLOC(capability, sizeof(GLint)); - glGetIntegerv(GL_COMPRESSED_TEXTURE_FORMATS, compFormats); - for (int i = 0; i < capability; i++) TRACELOG(RL_LOG_INFO, " %s", rlGetCompressedFormatName(compFormats[i])); - RL_FREE(compFormats); - -#if defined(GRAPHICS_API_OPENGL_43) - glGetIntegerv(GL_MAX_VERTEX_ATTRIB_BINDINGS, &capability); - TRACELOG(RL_LOG_INFO, " GL_MAX_VERTEX_ATTRIB_BINDINGS: %i", capability); - glGetIntegerv(GL_MAX_UNIFORM_LOCATIONS, &capability); - TRACELOG(RL_LOG_INFO, " GL_MAX_UNIFORM_LOCATIONS: %i", capability); -#endif // GRAPHICS_API_OPENGL_43 -#else // RLGL_SHOW_GL_DETAILS_INFO - - // Show some basic info about GL supported features - if (RLGL.ExtSupported.vao) TRACELOG(RL_LOG_INFO, "GL: VAO extension detected, VAO functions loaded successfully"); - else TRACELOG(RL_LOG_WARNING, "GL: VAO extension not found, VAO not supported"); - if (RLGL.ExtSupported.texNPOT) TRACELOG(RL_LOG_INFO, "GL: NPOT textures extension detected, full NPOT textures supported"); - else TRACELOG(RL_LOG_WARNING, "GL: NPOT textures extension not found, limited NPOT support (no-mipmaps, no-repeat)"); - if (RLGL.ExtSupported.texCompDXT) TRACELOG(RL_LOG_INFO, "GL: DXT compressed textures supported"); - if (RLGL.ExtSupported.texCompETC1) TRACELOG(RL_LOG_INFO, "GL: ETC1 compressed textures supported"); - if (RLGL.ExtSupported.texCompETC2) TRACELOG(RL_LOG_INFO, "GL: ETC2/EAC compressed textures supported"); - if (RLGL.ExtSupported.texCompPVRT) TRACELOG(RL_LOG_INFO, "GL: PVRT compressed textures supported"); - if (RLGL.ExtSupported.texCompASTC) TRACELOG(RL_LOG_INFO, "GL: ASTC compressed textures supported"); - if (RLGL.ExtSupported.computeShader) TRACELOG(RL_LOG_INFO, "GL: Compute shaders supported"); - if (RLGL.ExtSupported.ssbo) TRACELOG(RL_LOG_INFO, "GL: Shader storage buffer objects supported"); -#endif // RLGL_SHOW_GL_DETAILS_INFO - -#endif // GRAPHICS_API_OPENGL_33 || GRAPHICS_API_OPENGL_ES2 -} - -// Get current OpenGL version -int rlGetVersion(void) -{ - int glVersion = 0; -#if defined(GRAPHICS_API_OPENGL_11) - glVersion = RL_OPENGL_11; -#endif -#if defined(GRAPHICS_API_OPENGL_21) - glVersion = RL_OPENGL_21; -#elif defined(GRAPHICS_API_OPENGL_43) - glVersion = RL_OPENGL_43; -#elif defined(GRAPHICS_API_OPENGL_33) - glVersion = RL_OPENGL_33; -#endif -#if defined(GRAPHICS_API_OPENGL_ES3) - glVersion = RL_OPENGL_ES_30; -#elif defined(GRAPHICS_API_OPENGL_ES2) - glVersion = RL_OPENGL_ES_20; -#endif - - return glVersion; -} - -// Set current framebuffer width -void rlSetFramebufferWidth(int width) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - RLGL.State.framebufferWidth = width; -#endif -} - -// Set current framebuffer height -void rlSetFramebufferHeight(int height) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - RLGL.State.framebufferHeight = height; -#endif -} - -// Get default framebuffer width -int rlGetFramebufferWidth(void) -{ - int width = 0; -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - width = RLGL.State.framebufferWidth; -#endif - return width; -} - -// Get default framebuffer height -int rlGetFramebufferHeight(void) -{ - int height = 0; -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - height = RLGL.State.framebufferHeight; -#endif - return height; -} - -// Get default internal texture (white texture) -// NOTE: Default texture is a 1x1 pixel UNCOMPRESSED_R8G8B8A8 -unsigned int rlGetTextureIdDefault(void) -{ - unsigned int id = 0; -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - id = RLGL.State.defaultTextureId; -#endif - return id; -} - -// Get default shader id -unsigned int rlGetShaderIdDefault(void) -{ - unsigned int id = 0; -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - id = RLGL.State.defaultShaderId; -#endif - return id; -} - -// Get default shader locs -int *rlGetShaderLocsDefault(void) -{ - int *locs = NULL; -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - locs = RLGL.State.defaultShaderLocs; -#endif - return locs; -} - -// Render batch management -//------------------------------------------------------------------------------------------------ -// Load render batch -rlRenderBatch rlLoadRenderBatch(int numBuffers, int bufferElements) -{ - rlRenderBatch batch = { 0 }; - -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - // Initialize CPU (RAM) vertex buffers (position, texcoord, color data and indexes) - //-------------------------------------------------------------------------------------------- - batch.vertexBuffer = (rlVertexBuffer *)RL_MALLOC(numBuffers*sizeof(rlVertexBuffer)); - - for (int i = 0; i < numBuffers; i++) - { - batch.vertexBuffer[i].elementCount = bufferElements; - - batch.vertexBuffer[i].vertices = (float *)RL_MALLOC(bufferElements*3*4*sizeof(float)); // 3 float by vertex, 4 vertex by quad - batch.vertexBuffer[i].texcoords = (float *)RL_MALLOC(bufferElements*2*4*sizeof(float)); // 2 float by texcoord, 4 texcoord by quad - batch.vertexBuffer[i].normals = (float *)RL_MALLOC(bufferElements*3*4*sizeof(float)); // 3 float by vertex, 4 vertex by quad - batch.vertexBuffer[i].colors = (unsigned char *)RL_MALLOC(bufferElements*4*4*sizeof(unsigned char)); // 4 float by color, 4 colors by quad -#if defined(GRAPHICS_API_OPENGL_33) - batch.vertexBuffer[i].indices = (unsigned int *)RL_MALLOC(bufferElements*6*sizeof(unsigned int)); // 6 int by quad (indices) -#endif -#if defined(GRAPHICS_API_OPENGL_ES2) - batch.vertexBuffer[i].indices = (unsigned short *)RL_MALLOC(bufferElements*6*sizeof(unsigned short)); // 6 int by quad (indices) -#endif - - for (int j = 0; j < (3*4*bufferElements); j++) batch.vertexBuffer[i].vertices[j] = 0.0f; - for (int j = 0; j < (2*4*bufferElements); j++) batch.vertexBuffer[i].texcoords[j] = 0.0f; - for (int j = 0; j < (3*4*bufferElements); j++) batch.vertexBuffer[i].normals[j] = 0.0f; - for (int j = 0; j < (4*4*bufferElements); j++) batch.vertexBuffer[i].colors[j] = 0; - - int k = 0; - - // Indices can be initialized right now - for (int j = 0; j < (6*bufferElements); j += 6) - { - batch.vertexBuffer[i].indices[j] = 4*k; - batch.vertexBuffer[i].indices[j + 1] = 4*k + 1; - batch.vertexBuffer[i].indices[j + 2] = 4*k + 2; - batch.vertexBuffer[i].indices[j + 3] = 4*k; - batch.vertexBuffer[i].indices[j + 4] = 4*k + 2; - batch.vertexBuffer[i].indices[j + 5] = 4*k + 3; - - k++; - } - - RLGL.State.vertexCounter = 0; - } - - TRACELOG(RL_LOG_INFO, "RLGL: Render batch vertex buffers loaded successfully in RAM (CPU)"); - //-------------------------------------------------------------------------------------------- - - // Upload to GPU (VRAM) vertex data and initialize VAOs/VBOs - //-------------------------------------------------------------------------------------------- - for (int i = 0; i < numBuffers; i++) - { - if (RLGL.ExtSupported.vao) - { - // Initialize Quads VAO - glGenVertexArrays(1, &batch.vertexBuffer[i].vaoId); - glBindVertexArray(batch.vertexBuffer[i].vaoId); - } - - // Quads - Vertex buffers binding and attributes enable - // Vertex position buffer (shader-location = 0) - glGenBuffers(1, &batch.vertexBuffer[i].vboId[0]); - glBindBuffer(GL_ARRAY_BUFFER, batch.vertexBuffer[i].vboId[0]); - glBufferData(GL_ARRAY_BUFFER, bufferElements*3*4*sizeof(float), batch.vertexBuffer[i].vertices, GL_DYNAMIC_DRAW); - glEnableVertexAttribArray(RLGL.State.currentShaderLocs[RL_SHADER_LOC_VERTEX_POSITION]); - glVertexAttribPointer(RLGL.State.currentShaderLocs[RL_SHADER_LOC_VERTEX_POSITION], 3, GL_FLOAT, 0, 0, 0); - - // Vertex texcoord buffer (shader-location = 1) - glGenBuffers(1, &batch.vertexBuffer[i].vboId[1]); - glBindBuffer(GL_ARRAY_BUFFER, batch.vertexBuffer[i].vboId[1]); - glBufferData(GL_ARRAY_BUFFER, bufferElements*2*4*sizeof(float), batch.vertexBuffer[i].texcoords, GL_DYNAMIC_DRAW); - glEnableVertexAttribArray(RLGL.State.currentShaderLocs[RL_SHADER_LOC_VERTEX_TEXCOORD01]); - glVertexAttribPointer(RLGL.State.currentShaderLocs[RL_SHADER_LOC_VERTEX_TEXCOORD01], 2, GL_FLOAT, 0, 0, 0); - - // Vertex normal buffer (shader-location = 2) - glGenBuffers(1, &batch.vertexBuffer[i].vboId[2]); - glBindBuffer(GL_ARRAY_BUFFER, batch.vertexBuffer[i].vboId[2]); - glBufferData(GL_ARRAY_BUFFER, bufferElements*3*4*sizeof(float), batch.vertexBuffer[i].normals, GL_DYNAMIC_DRAW); - glEnableVertexAttribArray(RLGL.State.currentShaderLocs[RL_SHADER_LOC_VERTEX_NORMAL]); - glVertexAttribPointer(RLGL.State.currentShaderLocs[RL_SHADER_LOC_VERTEX_NORMAL], 3, GL_FLOAT, 0, 0, 0); - - // Vertex color buffer (shader-location = 3) - glGenBuffers(1, &batch.vertexBuffer[i].vboId[3]); - glBindBuffer(GL_ARRAY_BUFFER, batch.vertexBuffer[i].vboId[3]); - glBufferData(GL_ARRAY_BUFFER, bufferElements*4*4*sizeof(unsigned char), batch.vertexBuffer[i].colors, GL_DYNAMIC_DRAW); - glEnableVertexAttribArray(RLGL.State.currentShaderLocs[RL_SHADER_LOC_VERTEX_COLOR]); - glVertexAttribPointer(RLGL.State.currentShaderLocs[RL_SHADER_LOC_VERTEX_COLOR], 4, GL_UNSIGNED_BYTE, GL_TRUE, 0, 0); - - // Fill index buffer - glGenBuffers(1, &batch.vertexBuffer[i].vboId[4]); - glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, batch.vertexBuffer[i].vboId[4]); -#if defined(GRAPHICS_API_OPENGL_33) - glBufferData(GL_ELEMENT_ARRAY_BUFFER, bufferElements*6*sizeof(int), batch.vertexBuffer[i].indices, GL_STATIC_DRAW); -#endif -#if defined(GRAPHICS_API_OPENGL_ES2) - glBufferData(GL_ELEMENT_ARRAY_BUFFER, bufferElements*6*sizeof(short), batch.vertexBuffer[i].indices, GL_STATIC_DRAW); -#endif - } - - TRACELOG(RL_LOG_INFO, "RLGL: Render batch vertex buffers loaded successfully in VRAM (GPU)"); - - // Unbind the current VAO - if (RLGL.ExtSupported.vao) glBindVertexArray(0); - //-------------------------------------------------------------------------------------------- - - // Init draw calls tracking system - //-------------------------------------------------------------------------------------------- - batch.draws = (rlDrawCall *)RL_MALLOC(RL_DEFAULT_BATCH_DRAWCALLS*sizeof(rlDrawCall)); - - for (int i = 0; i < RL_DEFAULT_BATCH_DRAWCALLS; i++) - { - batch.draws[i].mode = RL_QUADS; - batch.draws[i].vertexCount = 0; - batch.draws[i].vertexAlignment = 0; - //batch.draws[i].vaoId = 0; - //batch.draws[i].shaderId = 0; - batch.draws[i].textureId = RLGL.State.defaultTextureId; - //batch.draws[i].RLGL.State.projection = rlMatrixIdentity(); - //batch.draws[i].RLGL.State.modelview = rlMatrixIdentity(); - } - - batch.bufferCount = numBuffers; // Record buffer count - batch.drawCounter = 1; // Reset draws counter - batch.currentDepth = -1.0f; // Reset depth value - //-------------------------------------------------------------------------------------------- -#endif - - return batch; -} - -// Unload default internal buffers vertex data from CPU and GPU -void rlUnloadRenderBatch(rlRenderBatch batch) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - // Unbind everything - glBindBuffer(GL_ARRAY_BUFFER, 0); - glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, 0); - - // Unload all vertex buffers data - for (int i = 0; i < batch.bufferCount; i++) - { - // Unbind VAO attribs data - if (RLGL.ExtSupported.vao) - { - glBindVertexArray(batch.vertexBuffer[i].vaoId); - glDisableVertexAttribArray(RL_DEFAULT_SHADER_ATTRIB_LOCATION_POSITION); - glDisableVertexAttribArray(RL_DEFAULT_SHADER_ATTRIB_LOCATION_TEXCOORD); - glDisableVertexAttribArray(RL_DEFAULT_SHADER_ATTRIB_LOCATION_NORMAL); - glDisableVertexAttribArray(RL_DEFAULT_SHADER_ATTRIB_LOCATION_COLOR); - glBindVertexArray(0); - } - - // Delete VBOs from GPU (VRAM) - glDeleteBuffers(1, &batch.vertexBuffer[i].vboId[0]); - glDeleteBuffers(1, &batch.vertexBuffer[i].vboId[1]); - glDeleteBuffers(1, &batch.vertexBuffer[i].vboId[2]); - glDeleteBuffers(1, &batch.vertexBuffer[i].vboId[3]); - glDeleteBuffers(1, &batch.vertexBuffer[i].vboId[4]); - - // Delete VAOs from GPU (VRAM) - if (RLGL.ExtSupported.vao) glDeleteVertexArrays(1, &batch.vertexBuffer[i].vaoId); - - // Free vertex arrays memory from CPU (RAM) - RL_FREE(batch.vertexBuffer[i].vertices); - RL_FREE(batch.vertexBuffer[i].texcoords); - RL_FREE(batch.vertexBuffer[i].normals); - RL_FREE(batch.vertexBuffer[i].colors); - RL_FREE(batch.vertexBuffer[i].indices); - } - - // Unload arrays - RL_FREE(batch.vertexBuffer); - RL_FREE(batch.draws); -#endif -} - -// Draw render batch -// NOTE: We require a pointer to reset batch and increase current buffer (multi-buffer) -void rlDrawRenderBatch(rlRenderBatch *batch) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - // Update batch vertex buffers - //------------------------------------------------------------------------------------------------------------ - // NOTE: If there is not vertex data, buffers doesn't need to be updated (vertexCount > 0) - // TODO: If no data changed on the CPU arrays --> No need to re-update GPU arrays (use a change detector flag?) - if (RLGL.State.vertexCounter > 0) - { - // Activate elements VAO - if (RLGL.ExtSupported.vao) glBindVertexArray(batch->vertexBuffer[batch->currentBuffer].vaoId); - - // Vertex positions buffer - glBindBuffer(GL_ARRAY_BUFFER, batch->vertexBuffer[batch->currentBuffer].vboId[0]); - glBufferSubData(GL_ARRAY_BUFFER, 0, RLGL.State.vertexCounter*3*sizeof(float), batch->vertexBuffer[batch->currentBuffer].vertices); - //glBufferData(GL_ARRAY_BUFFER, sizeof(float)*3*4*batch->vertexBuffer[batch->currentBuffer].elementCount, batch->vertexBuffer[batch->currentBuffer].vertices, GL_DYNAMIC_DRAW); // Update all buffer - - // Texture coordinates buffer - glBindBuffer(GL_ARRAY_BUFFER, batch->vertexBuffer[batch->currentBuffer].vboId[1]); - glBufferSubData(GL_ARRAY_BUFFER, 0, RLGL.State.vertexCounter*2*sizeof(float), batch->vertexBuffer[batch->currentBuffer].texcoords); - //glBufferData(GL_ARRAY_BUFFER, sizeof(float)*2*4*batch->vertexBuffer[batch->currentBuffer].elementCount, batch->vertexBuffer[batch->currentBuffer].texcoords, GL_DYNAMIC_DRAW); // Update all buffer - - // Normals buffer - glBindBuffer(GL_ARRAY_BUFFER, batch->vertexBuffer[batch->currentBuffer].vboId[2]); - glBufferSubData(GL_ARRAY_BUFFER, 0, RLGL.State.vertexCounter*3*sizeof(float), batch->vertexBuffer[batch->currentBuffer].normals); - //glBufferData(GL_ARRAY_BUFFER, sizeof(float)*3*4*batch->vertexBuffer[batch->currentBuffer].elementCount, batch->vertexBuffer[batch->currentBuffer].normals, GL_DYNAMIC_DRAW); // Update all buffer - - // Colors buffer - glBindBuffer(GL_ARRAY_BUFFER, batch->vertexBuffer[batch->currentBuffer].vboId[3]); - glBufferSubData(GL_ARRAY_BUFFER, 0, RLGL.State.vertexCounter*4*sizeof(unsigned char), batch->vertexBuffer[batch->currentBuffer].colors); - //glBufferData(GL_ARRAY_BUFFER, sizeof(float)*4*4*batch->vertexBuffer[batch->currentBuffer].elementCount, batch->vertexBuffer[batch->currentBuffer].colors, GL_DYNAMIC_DRAW); // Update all buffer - - // NOTE: glMapBuffer() causes sync issue - // If GPU is working with this buffer, glMapBuffer() will wait(stall) until GPU to finish its job - // To avoid waiting (idle), you can call first glBufferData() with NULL pointer before glMapBuffer() - // If you do that, the previous data in PBO will be discarded and glMapBuffer() returns a new - // allocated pointer immediately even if GPU is still working with the previous data - - // Another option: map the buffer object into client's memory - // Probably this code could be moved somewhere else... - // batch->vertexBuffer[batch->currentBuffer].vertices = (float *)glMapBuffer(GL_ARRAY_BUFFER, GL_READ_WRITE); - // if (batch->vertexBuffer[batch->currentBuffer].vertices) - // { - // Update vertex data - // } - // glUnmapBuffer(GL_ARRAY_BUFFER); - - // Unbind the current VAO - if (RLGL.ExtSupported.vao) glBindVertexArray(0); - } - //------------------------------------------------------------------------------------------------------------ - - // Draw batch vertex buffers (considering VR stereo if required) - //------------------------------------------------------------------------------------------------------------ - Matrix matProjection = RLGL.State.projection; - Matrix matModelView = RLGL.State.modelview; - - int eyeCount = 1; - if (RLGL.State.stereoRender) eyeCount = 2; - - for (int eye = 0; eye < eyeCount; eye++) - { - if (eyeCount == 2) - { - // Setup current eye viewport (half screen width) - rlViewport(eye*RLGL.State.framebufferWidth/2, 0, RLGL.State.framebufferWidth/2, RLGL.State.framebufferHeight); - - // Set current eye view offset to modelview matrix - rlSetMatrixModelview(rlMatrixMultiply(matModelView, RLGL.State.viewOffsetStereo[eye])); - // Set current eye projection matrix - rlSetMatrixProjection(RLGL.State.projectionStereo[eye]); - } - - // Draw buffers - if (RLGL.State.vertexCounter > 0) - { - // Set current shader and upload current MVP matrix - glUseProgram(RLGL.State.currentShaderId); - - // Create modelview-projection matrix and upload to shader - Matrix matMVP = rlMatrixMultiply(RLGL.State.modelview, RLGL.State.projection); - glUniformMatrix4fv(RLGL.State.currentShaderLocs[RL_SHADER_LOC_MATRIX_MVP], 1, false, rlMatrixToFloat(matMVP)); - - if (RLGL.State.currentShaderLocs[RL_SHADER_LOC_MATRIX_PROJECTION] != -1) - { - glUniformMatrix4fv(RLGL.State.currentShaderLocs[RL_SHADER_LOC_MATRIX_PROJECTION], 1, false, rlMatrixToFloat(RLGL.State.projection)); - } - - // WARNING: For the following setup of the view, model, and normal matrices, it is expected that - // transformations and rendering occur between rlPushMatrix() and rlPopMatrix() - - if (RLGL.State.currentShaderLocs[RL_SHADER_LOC_MATRIX_VIEW] != -1) - { - glUniformMatrix4fv(RLGL.State.currentShaderLocs[RL_SHADER_LOC_MATRIX_VIEW], 1, false, rlMatrixToFloat(RLGL.State.modelview)); - } - - if (RLGL.State.currentShaderLocs[RL_SHADER_LOC_MATRIX_MODEL] != -1) - { - glUniformMatrix4fv(RLGL.State.currentShaderLocs[RL_SHADER_LOC_MATRIX_MODEL], 1, false, rlMatrixToFloat(RLGL.State.transform)); - } - - if (RLGL.State.currentShaderLocs[RL_SHADER_LOC_MATRIX_NORMAL] != -1) - { - glUniformMatrix4fv(RLGL.State.currentShaderLocs[RL_SHADER_LOC_MATRIX_NORMAL], 1, false, rlMatrixToFloat(rlMatrixTranspose(rlMatrixInvert(RLGL.State.transform)))); - } - - if (RLGL.ExtSupported.vao) glBindVertexArray(batch->vertexBuffer[batch->currentBuffer].vaoId); - else - { - // Bind vertex attrib: position (shader-location = 0) - glBindBuffer(GL_ARRAY_BUFFER, batch->vertexBuffer[batch->currentBuffer].vboId[0]); - glVertexAttribPointer(RLGL.State.currentShaderLocs[RL_SHADER_LOC_VERTEX_POSITION], 3, GL_FLOAT, 0, 0, 0); - glEnableVertexAttribArray(RLGL.State.currentShaderLocs[RL_SHADER_LOC_VERTEX_POSITION]); - - // Bind vertex attrib: texcoord (shader-location = 1) - glBindBuffer(GL_ARRAY_BUFFER, batch->vertexBuffer[batch->currentBuffer].vboId[1]); - glVertexAttribPointer(RLGL.State.currentShaderLocs[RL_SHADER_LOC_VERTEX_TEXCOORD01], 2, GL_FLOAT, 0, 0, 0); - glEnableVertexAttribArray(RLGL.State.currentShaderLocs[RL_SHADER_LOC_VERTEX_TEXCOORD01]); - - // Bind vertex attrib: normal (shader-location = 2) - glBindBuffer(GL_ARRAY_BUFFER, batch->vertexBuffer[batch->currentBuffer].vboId[2]); - glVertexAttribPointer(RLGL.State.currentShaderLocs[RL_SHADER_LOC_VERTEX_NORMAL], 3, GL_FLOAT, 0, 0, 0); - glEnableVertexAttribArray(RLGL.State.currentShaderLocs[RL_SHADER_LOC_VERTEX_NORMAL]); - - // Bind vertex attrib: color (shader-location = 3) - glBindBuffer(GL_ARRAY_BUFFER, batch->vertexBuffer[batch->currentBuffer].vboId[3]); - glVertexAttribPointer(RLGL.State.currentShaderLocs[RL_SHADER_LOC_VERTEX_COLOR], 4, GL_UNSIGNED_BYTE, GL_TRUE, 0, 0); - glEnableVertexAttribArray(RLGL.State.currentShaderLocs[RL_SHADER_LOC_VERTEX_COLOR]); - - glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, batch->vertexBuffer[batch->currentBuffer].vboId[4]); - } - - // Setup some default shader values - glUniform4f(RLGL.State.currentShaderLocs[RL_SHADER_LOC_COLOR_DIFFUSE], 1.0f, 1.0f, 1.0f, 1.0f); - glUniform1i(RLGL.State.currentShaderLocs[RL_SHADER_LOC_MAP_DIFFUSE], 0); // Active default sampler2D: texture0 - - // Activate additional sampler textures - // Those additional textures will be common for all draw calls of the batch - for (int i = 0; i < RL_DEFAULT_BATCH_MAX_TEXTURE_UNITS; i++) - { - if (RLGL.State.activeTextureId[i] > 0) - { - glActiveTexture(GL_TEXTURE0 + 1 + i); - glBindTexture(GL_TEXTURE_2D, RLGL.State.activeTextureId[i]); - } - } - - // Activate default sampler2D texture0 (one texture is always active for default batch shader) - // NOTE: Batch system accumulates calls by texture0 changes, additional textures are enabled for all the draw calls - glActiveTexture(GL_TEXTURE0); - - for (int i = 0, vertexOffset = 0; i < batch->drawCounter; i++) - { - // Bind current draw call texture, activated as GL_TEXTURE0 and Bound to sampler2D texture0 by default - glBindTexture(GL_TEXTURE_2D, batch->draws[i].textureId); - - if ((batch->draws[i].mode == RL_LINES) || (batch->draws[i].mode == RL_TRIANGLES)) glDrawArrays(batch->draws[i].mode, vertexOffset, batch->draws[i].vertexCount); - else - { - #if defined(GRAPHICS_API_OPENGL_33) - // We need to define the number of indices to be processed: elementCount*6 - // NOTE: The final parameter tells the GPU the offset in bytes from the - // start of the index buffer to the location of the first index to process - glDrawElements(GL_TRIANGLES, batch->draws[i].vertexCount/4*6, GL_UNSIGNED_INT, (GLvoid *)(vertexOffset/4*6*sizeof(GLuint))); - #endif - #if defined(GRAPHICS_API_OPENGL_ES2) - glDrawElements(GL_TRIANGLES, batch->draws[i].vertexCount/4*6, GL_UNSIGNED_SHORT, (GLvoid *)(vertexOffset/4*6*sizeof(GLushort))); - #endif - } - - vertexOffset += (batch->draws[i].vertexCount + batch->draws[i].vertexAlignment); - } - - if (!RLGL.ExtSupported.vao) - { - glBindBuffer(GL_ARRAY_BUFFER, 0); - glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, 0); - } - - glBindTexture(GL_TEXTURE_2D, 0); // Unbind textures - } - - if (RLGL.ExtSupported.vao) glBindVertexArray(0); // Unbind VAO - - glUseProgram(0); // Unbind shader program - } - - // Restore viewport to default measures - if (eyeCount == 2) rlViewport(0, 0, RLGL.State.framebufferWidth, RLGL.State.framebufferHeight); - //------------------------------------------------------------------------------------------------------------ - - // Reset batch buffers - //------------------------------------------------------------------------------------------------------------ - // Reset vertex counter for next frame - RLGL.State.vertexCounter = 0; - - // Reset depth for next draw - batch->currentDepth = -1.0f; - - // Restore projection/modelview matrices - RLGL.State.projection = matProjection; - RLGL.State.modelview = matModelView; - - // Reset RLGL.currentBatch->draws array - for (int i = 0; i < RL_DEFAULT_BATCH_DRAWCALLS; i++) - { - batch->draws[i].mode = RL_QUADS; - batch->draws[i].vertexCount = 0; - batch->draws[i].textureId = RLGL.State.defaultTextureId; - } - - // Reset active texture units for next batch - for (int i = 0; i < RL_DEFAULT_BATCH_MAX_TEXTURE_UNITS; i++) RLGL.State.activeTextureId[i] = 0; - - // Reset draws counter to one draw for the batch - batch->drawCounter = 1; - //------------------------------------------------------------------------------------------------------------ - - // Change to next buffer in the list (in case of multi-buffering) - batch->currentBuffer++; - if (batch->currentBuffer >= batch->bufferCount) batch->currentBuffer = 0; -#endif -} - -// Set the active render batch for rlgl -void rlSetRenderBatchActive(rlRenderBatch *batch) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - rlDrawRenderBatch(RLGL.currentBatch); - - if (batch != NULL) RLGL.currentBatch = batch; - else RLGL.currentBatch = &RLGL.defaultBatch; -#endif -} - -// Update and draw internal render batch -void rlDrawRenderBatchActive(void) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - rlDrawRenderBatch(RLGL.currentBatch); // NOTE: Stereo rendering is checked inside -#endif -} - -// Check internal buffer overflow for a given number of vertex -// and force a rlRenderBatch draw call if required -bool rlCheckRenderBatchLimit(int vCount) -{ - bool overflow = false; - -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - if ((RLGL.State.vertexCounter + vCount) >= - (RLGL.currentBatch->vertexBuffer[RLGL.currentBatch->currentBuffer].elementCount*4)) - { - overflow = true; - - // Store current primitive drawing mode and texture id - int currentMode = RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].mode; - int currentTexture = RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].textureId; - - rlDrawRenderBatch(RLGL.currentBatch); // NOTE: Stereo rendering is checked inside - - // Restore state of last batch so we can continue adding vertices - RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].mode = currentMode; - RLGL.currentBatch->draws[RLGL.currentBatch->drawCounter - 1].textureId = currentTexture; - } -#endif - - return overflow; -} - -// Textures data management -//----------------------------------------------------------------------------------------- -// Convert image data to OpenGL texture (returns OpenGL valid Id) -unsigned int rlLoadTexture(const void *data, int width, int height, int format, int mipmapCount) -{ - unsigned int id = 0; - - glBindTexture(GL_TEXTURE_2D, 0); // Free any old binding - - // Check texture format support by OpenGL 1.1 (compressed textures not supported) -#if defined(GRAPHICS_API_OPENGL_11) - if (format >= RL_PIXELFORMAT_COMPRESSED_DXT1_RGB) - { - TRACELOG(RL_LOG_WARNING, "GL: OpenGL 1.1 does not support GPU compressed texture formats"); - return id; - } -#else - if ((!RLGL.ExtSupported.texCompDXT) && ((format == RL_PIXELFORMAT_COMPRESSED_DXT1_RGB) || (format == RL_PIXELFORMAT_COMPRESSED_DXT1_RGBA) || - (format == RL_PIXELFORMAT_COMPRESSED_DXT3_RGBA) || (format == RL_PIXELFORMAT_COMPRESSED_DXT5_RGBA))) - { - TRACELOG(RL_LOG_WARNING, "GL: DXT compressed texture format not supported"); - return id; - } -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - if ((!RLGL.ExtSupported.texCompETC1) && (format == RL_PIXELFORMAT_COMPRESSED_ETC1_RGB)) - { - TRACELOG(RL_LOG_WARNING, "GL: ETC1 compressed texture format not supported"); - return id; - } - - if ((!RLGL.ExtSupported.texCompETC2) && ((format == RL_PIXELFORMAT_COMPRESSED_ETC2_RGB) || (format == RL_PIXELFORMAT_COMPRESSED_ETC2_EAC_RGBA))) - { - TRACELOG(RL_LOG_WARNING, "GL: ETC2 compressed texture format not supported"); - return id; - } - - if ((!RLGL.ExtSupported.texCompPVRT) && ((format == RL_PIXELFORMAT_COMPRESSED_PVRT_RGB) || (format == RL_PIXELFORMAT_COMPRESSED_PVRT_RGBA))) - { - TRACELOG(RL_LOG_WARNING, "GL: PVRT compressed texture format not supported"); - return id; - } - - if ((!RLGL.ExtSupported.texCompASTC) && ((format == RL_PIXELFORMAT_COMPRESSED_ASTC_4x4_RGBA) || (format == RL_PIXELFORMAT_COMPRESSED_ASTC_8x8_RGBA))) - { - TRACELOG(RL_LOG_WARNING, "GL: ASTC compressed texture format not supported"); - return id; - } -#endif -#endif // GRAPHICS_API_OPENGL_11 - - glPixelStorei(GL_UNPACK_ALIGNMENT, 1); - - glGenTextures(1, &id); // Generate texture id - - glBindTexture(GL_TEXTURE_2D, id); - - int mipWidth = width; - int mipHeight = height; - int mipOffset = 0; // Mipmap data offset, only used for tracelog - - // NOTE: Added pointer math separately from function to avoid UBSAN complaining - unsigned char *dataPtr = NULL; - if (data != NULL) dataPtr = (unsigned char *)data; - - // Load the different mipmap levels - for (int i = 0; i < mipmapCount; i++) - { - unsigned int mipSize = rlGetPixelDataSize(mipWidth, mipHeight, format); - - unsigned int glInternalFormat, glFormat, glType; - rlGetGlTextureFormats(format, &glInternalFormat, &glFormat, &glType); - - TRACELOGD("TEXTURE: Load mipmap level %i (%i x %i), size: %i, offset: %i", i, mipWidth, mipHeight, mipSize, mipOffset); - - if (glInternalFormat != 0) - { - if (format < RL_PIXELFORMAT_COMPRESSED_DXT1_RGB) glTexImage2D(GL_TEXTURE_2D, i, glInternalFormat, mipWidth, mipHeight, 0, glFormat, glType, dataPtr); -#if !defined(GRAPHICS_API_OPENGL_11) - else glCompressedTexImage2D(GL_TEXTURE_2D, i, glInternalFormat, mipWidth, mipHeight, 0, mipSize, dataPtr); -#endif - -#if defined(GRAPHICS_API_OPENGL_33) - if (format == RL_PIXELFORMAT_UNCOMPRESSED_GRAYSCALE) - { - GLint swizzleMask[] = { GL_RED, GL_RED, GL_RED, GL_ONE }; - glTexParameteriv(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_RGBA, swizzleMask); - } - else if (format == RL_PIXELFORMAT_UNCOMPRESSED_GRAY_ALPHA) - { -#if defined(GRAPHICS_API_OPENGL_21) - GLint swizzleMask[] = { GL_RED, GL_RED, GL_RED, GL_ALPHA }; -#elif defined(GRAPHICS_API_OPENGL_33) - GLint swizzleMask[] = { GL_RED, GL_RED, GL_RED, GL_GREEN }; -#endif - glTexParameteriv(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_RGBA, swizzleMask); - } -#endif - } - - mipWidth /= 2; - mipHeight /= 2; - mipOffset += mipSize; // Increment offset position to next mipmap - if (data != NULL) dataPtr += mipSize; // Increment data pointer to next mipmap - - // Security check for NPOT textures - if (mipWidth < 1) mipWidth = 1; - if (mipHeight < 1) mipHeight = 1; - } - - // Texture parameters configuration - // NOTE: glTexParameteri does NOT affect texture uploading, just the way it's used -#if defined(GRAPHICS_API_OPENGL_ES2) - // NOTE: OpenGL ES 2.0 with no GL_OES_texture_npot support (i.e. WebGL) has limited NPOT support, so CLAMP_TO_EDGE must be used - if (RLGL.ExtSupported.texNPOT) - { - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_REPEAT); // Set texture to repeat on x-axis - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_REPEAT); // Set texture to repeat on y-axis - } - else - { - // NOTE: If using negative texture coordinates (LoadOBJ()), it does not work! - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE); // Set texture to clamp on x-axis - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE); // Set texture to clamp on y-axis - } -#else - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_REPEAT); // Set texture to repeat on x-axis - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_REPEAT); // Set texture to repeat on y-axis -#endif - - // Magnification and minification filters - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST); // Alternative: GL_LINEAR - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST); // Alternative: GL_LINEAR - -#if defined(GRAPHICS_API_OPENGL_33) - if (mipmapCount > 1) - { - // Activate Trilinear filtering if mipmaps are available - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR_MIPMAP_LINEAR); - } -#endif - - // At this point we have the texture loaded in GPU and texture parameters configured - - // NOTE: If mipmaps were not in data, they are not generated automatically - - // Unbind current texture - glBindTexture(GL_TEXTURE_2D, 0); - - if (id > 0) TRACELOG(RL_LOG_INFO, "TEXTURE: [ID %i] Texture loaded successfully (%ix%i | %s | %i mipmaps)", id, width, height, rlGetPixelFormatName(format), mipmapCount); - else TRACELOG(RL_LOG_WARNING, "TEXTURE: Failed to load texture"); - - return id; -} - -// Load depth texture/renderbuffer (to be attached to fbo) -// WARNING: OpenGL ES 2.0 requires GL_OES_depth_texture and WebGL requires WEBGL_depth_texture extensions -unsigned int rlLoadTextureDepth(int width, int height, bool useRenderBuffer) -{ - unsigned int id = 0; - -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - // In case depth textures not supported, we force renderbuffer usage - if (!RLGL.ExtSupported.texDepth) useRenderBuffer = true; - - // NOTE: We let the implementation to choose the best bit-depth - // Possible formats: GL_DEPTH_COMPONENT16, GL_DEPTH_COMPONENT24, GL_DEPTH_COMPONENT32 and GL_DEPTH_COMPONENT32F - unsigned int glInternalFormat = GL_DEPTH_COMPONENT; - -#if (defined(GRAPHICS_API_OPENGL_ES2) || defined(GRAPHICS_API_OPENGL_ES3)) - // WARNING: WebGL platform requires unsized internal format definition (GL_DEPTH_COMPONENT) - // while other platforms using OpenGL ES 2.0 require/support sized internal formats depending on the GPU capabilities - if (!RLGL.ExtSupported.texDepthWebGL || useRenderBuffer) - { - if (RLGL.ExtSupported.maxDepthBits == 32) glInternalFormat = GL_DEPTH_COMPONENT32_OES; - else if (RLGL.ExtSupported.maxDepthBits == 24) glInternalFormat = GL_DEPTH_COMPONENT24_OES; - else glInternalFormat = GL_DEPTH_COMPONENT16; - } -#endif - - if (!useRenderBuffer && RLGL.ExtSupported.texDepth) - { - glGenTextures(1, &id); - glBindTexture(GL_TEXTURE_2D, id); - glTexImage2D(GL_TEXTURE_2D, 0, glInternalFormat, width, height, 0, GL_DEPTH_COMPONENT, GL_UNSIGNED_INT, NULL); - - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE); - - glBindTexture(GL_TEXTURE_2D, 0); - - TRACELOG(RL_LOG_INFO, "TEXTURE: Depth texture loaded successfully"); - } - else - { - // Create the renderbuffer that will serve as the depth attachment for the framebuffer - // NOTE: A renderbuffer is simpler than a texture and could offer better performance on embedded devices - glGenRenderbuffers(1, &id); - glBindRenderbuffer(GL_RENDERBUFFER, id); - glRenderbufferStorage(GL_RENDERBUFFER, glInternalFormat, width, height); - - glBindRenderbuffer(GL_RENDERBUFFER, 0); - - TRACELOG(RL_LOG_INFO, "TEXTURE: [ID %i] Depth renderbuffer loaded successfully (%i bits)", id, (RLGL.ExtSupported.maxDepthBits >= 24)? RLGL.ExtSupported.maxDepthBits : 16); - } -#endif - - return id; -} - -// Load texture cubemap -// NOTE: Cubemap data is expected to be 6 images in a single data array (one after the other), -// expected the following convention: +X, -X, +Y, -Y, +Z, -Z -unsigned int rlLoadTextureCubemap(const void *data, int size, int format, int mipmapCount) -{ - unsigned int id = 0; - -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - int mipSize = size; - - // NOTE: Added pointer math separately from function to avoid UBSAN complaining - unsigned char *dataPtr = NULL; - if (data != NULL) dataPtr = (unsigned char *)data; - - unsigned int dataSize = rlGetPixelDataSize(size, size, format); - - glGenTextures(1, &id); - glBindTexture(GL_TEXTURE_CUBE_MAP, id); - - unsigned int glInternalFormat, glFormat, glType; - rlGetGlTextureFormats(format, &glInternalFormat, &glFormat, &glType); - - if (glInternalFormat != 0) - { - // Load cubemap faces/mipmaps - for (int i = 0; i < 6*mipmapCount; i++) - { - int mipmapLevel = i/6; - int face = i%6; - - if (data == NULL) - { - if (format < RL_PIXELFORMAT_COMPRESSED_DXT1_RGB) - { - if ((format == RL_PIXELFORMAT_UNCOMPRESSED_R32) || - (format == RL_PIXELFORMAT_UNCOMPRESSED_R32G32B32A32) || - (format == RL_PIXELFORMAT_UNCOMPRESSED_R16) || - (format == RL_PIXELFORMAT_UNCOMPRESSED_R16G16B16A16)) TRACELOG(RL_LOG_WARNING, "TEXTURES: Cubemap requested format not supported"); - else glTexImage2D(GL_TEXTURE_CUBE_MAP_POSITIVE_X + face, mipmapLevel, glInternalFormat, mipSize, mipSize, 0, glFormat, glType, NULL); - } - else TRACELOG(RL_LOG_WARNING, "TEXTURES: Empty cubemap creation does not support compressed format"); - } - else - { - if (format < RL_PIXELFORMAT_COMPRESSED_DXT1_RGB) glTexImage2D(GL_TEXTURE_CUBE_MAP_POSITIVE_X + face, mipmapLevel, glInternalFormat, mipSize, mipSize, 0, glFormat, glType, (unsigned char *)dataPtr + face*dataSize); - else glCompressedTexImage2D(GL_TEXTURE_CUBE_MAP_POSITIVE_X + face, mipmapLevel, glInternalFormat, mipSize, mipSize, 0, dataSize, (unsigned char *)dataPtr + face*dataSize); - } - -#if defined(GRAPHICS_API_OPENGL_33) - if (format == RL_PIXELFORMAT_UNCOMPRESSED_GRAYSCALE) - { - GLint swizzleMask[] = { GL_RED, GL_RED, GL_RED, GL_ONE }; - glTexParameteriv(GL_TEXTURE_CUBE_MAP, GL_TEXTURE_SWIZZLE_RGBA, swizzleMask); - } - else if (format == RL_PIXELFORMAT_UNCOMPRESSED_GRAY_ALPHA) - { -#if defined(GRAPHICS_API_OPENGL_21) - GLint swizzleMask[] = { GL_RED, GL_RED, GL_RED, GL_ALPHA }; -#elif defined(GRAPHICS_API_OPENGL_33) - GLint swizzleMask[] = { GL_RED, GL_RED, GL_RED, GL_GREEN }; -#endif - glTexParameteriv(GL_TEXTURE_CUBE_MAP, GL_TEXTURE_SWIZZLE_RGBA, swizzleMask); - } -#endif - if (face == 5) - { - mipSize /= 2; - if (data != NULL) dataPtr += dataSize*6; // Increment data pointer to next mipmap - - // Security check for NPOT textures - if (mipSize < 1) mipSize = 1; - - dataSize = rlGetPixelDataSize(mipSize, mipSize, format); - } - } - } - - // Set cubemap texture sampling parameters - if (mipmapCount > 1) glTexParameteri(GL_TEXTURE_CUBE_MAP, GL_TEXTURE_MIN_FILTER, GL_LINEAR_MIPMAP_LINEAR); - else glTexParameteri(GL_TEXTURE_CUBE_MAP, GL_TEXTURE_MIN_FILTER, GL_LINEAR); - - glTexParameteri(GL_TEXTURE_CUBE_MAP, GL_TEXTURE_MAG_FILTER, GL_LINEAR); - glTexParameteri(GL_TEXTURE_CUBE_MAP, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE); - glTexParameteri(GL_TEXTURE_CUBE_MAP, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE); -#if defined(GRAPHICS_API_OPENGL_33) - glTexParameteri(GL_TEXTURE_CUBE_MAP, GL_TEXTURE_WRAP_R, GL_CLAMP_TO_EDGE); // Flag not supported on OpenGL ES 2.0 -#endif - - glBindTexture(GL_TEXTURE_CUBE_MAP, 0); -#endif - - if (id > 0) TRACELOG(RL_LOG_INFO, "TEXTURE: [ID %i] Cubemap texture loaded successfully (%ix%i)", id, size, size); - else TRACELOG(RL_LOG_WARNING, "TEXTURE: Failed to load cubemap texture"); - - return id; -} - -// Update already loaded texture in GPU with new data -// NOTE: We don't know safely if internal texture format is the expected one... -void rlUpdateTexture(unsigned int id, int offsetX, int offsetY, int width, int height, int format, const void *data) -{ - glBindTexture(GL_TEXTURE_2D, id); - - unsigned int glInternalFormat, glFormat, glType; - rlGetGlTextureFormats(format, &glInternalFormat, &glFormat, &glType); - - if ((glInternalFormat != 0) && (format < RL_PIXELFORMAT_COMPRESSED_DXT1_RGB)) - { - glTexSubImage2D(GL_TEXTURE_2D, 0, offsetX, offsetY, width, height, glFormat, glType, data); - } - else TRACELOG(RL_LOG_WARNING, "TEXTURE: [ID %i] Failed to update for current texture format (%i)", id, format); -} - -// Get OpenGL internal formats and data type from raylib PixelFormat -void rlGetGlTextureFormats(int format, unsigned int *glInternalFormat, unsigned int *glFormat, unsigned int *glType) -{ - *glInternalFormat = 0; - *glFormat = 0; - *glType = 0; - - switch (format) - { - #if defined(GRAPHICS_API_OPENGL_11) || defined(GRAPHICS_API_OPENGL_21) || defined(GRAPHICS_API_OPENGL_ES2) - // NOTE: on OpenGL ES 2.0 (WebGL), internalFormat must match format and options allowed are: GL_LUMINANCE, GL_RGB, GL_RGBA - case RL_PIXELFORMAT_UNCOMPRESSED_GRAYSCALE: *glInternalFormat = GL_LUMINANCE; *glFormat = GL_LUMINANCE; *glType = GL_UNSIGNED_BYTE; break; - case RL_PIXELFORMAT_UNCOMPRESSED_GRAY_ALPHA: *glInternalFormat = GL_LUMINANCE_ALPHA; *glFormat = GL_LUMINANCE_ALPHA; *glType = GL_UNSIGNED_BYTE; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R5G6B5: *glInternalFormat = GL_RGB; *glFormat = GL_RGB; *glType = GL_UNSIGNED_SHORT_5_6_5; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R8G8B8: *glInternalFormat = GL_RGB; *glFormat = GL_RGB; *glType = GL_UNSIGNED_BYTE; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R5G5B5A1: *glInternalFormat = GL_RGBA; *glFormat = GL_RGBA; *glType = GL_UNSIGNED_SHORT_5_5_5_1; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R4G4B4A4: *glInternalFormat = GL_RGBA; *glFormat = GL_RGBA; *glType = GL_UNSIGNED_SHORT_4_4_4_4; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R8G8B8A8: *glInternalFormat = GL_RGBA; *glFormat = GL_RGBA; *glType = GL_UNSIGNED_BYTE; break; - #if !defined(GRAPHICS_API_OPENGL_11) - #if defined(GRAPHICS_API_OPENGL_ES3) - case RL_PIXELFORMAT_UNCOMPRESSED_R32: if (RLGL.ExtSupported.texFloat32) *glInternalFormat = GL_R32F_EXT; *glFormat = GL_RED_EXT; *glType = GL_FLOAT; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R32G32B32: if (RLGL.ExtSupported.texFloat32) *glInternalFormat = GL_RGB32F_EXT; *glFormat = GL_RGB; *glType = GL_FLOAT; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R32G32B32A32: if (RLGL.ExtSupported.texFloat32) *glInternalFormat = GL_RGBA32F_EXT; *glFormat = GL_RGBA; *glType = GL_FLOAT; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R16: if (RLGL.ExtSupported.texFloat16) *glInternalFormat = GL_R16F_EXT; *glFormat = GL_RED_EXT; *glType = GL_HALF_FLOAT; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R16G16B16: if (RLGL.ExtSupported.texFloat16) *glInternalFormat = GL_RGB16F_EXT; *glFormat = GL_RGB; *glType = GL_HALF_FLOAT; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R16G16B16A16: if (RLGL.ExtSupported.texFloat16) *glInternalFormat = GL_RGBA16F_EXT; *glFormat = GL_RGBA; *glType = GL_HALF_FLOAT; break; - #else - case RL_PIXELFORMAT_UNCOMPRESSED_R32: if (RLGL.ExtSupported.texFloat32) *glInternalFormat = GL_LUMINANCE; *glFormat = GL_LUMINANCE; *glType = GL_FLOAT; break; // NOTE: Requires extension OES_texture_float - case RL_PIXELFORMAT_UNCOMPRESSED_R32G32B32: if (RLGL.ExtSupported.texFloat32) *glInternalFormat = GL_RGB; *glFormat = GL_RGB; *glType = GL_FLOAT; break; // NOTE: Requires extension OES_texture_float - case RL_PIXELFORMAT_UNCOMPRESSED_R32G32B32A32: if (RLGL.ExtSupported.texFloat32) *glInternalFormat = GL_RGBA; *glFormat = GL_RGBA; *glType = GL_FLOAT; break; // NOTE: Requires extension OES_texture_float - #if defined(GRAPHICS_API_OPENGL_21) - case RL_PIXELFORMAT_UNCOMPRESSED_R16: if (RLGL.ExtSupported.texFloat16) *glInternalFormat = GL_LUMINANCE; *glFormat = GL_LUMINANCE; *glType = GL_HALF_FLOAT_ARB; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R16G16B16: if (RLGL.ExtSupported.texFloat16) *glInternalFormat = GL_RGB; *glFormat = GL_RGB; *glType = GL_HALF_FLOAT_ARB; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R16G16B16A16: if (RLGL.ExtSupported.texFloat16) *glInternalFormat = GL_RGBA; *glFormat = GL_RGBA; *glType = GL_HALF_FLOAT_ARB; break; - #else // defined(GRAPHICS_API_OPENGL_ES2) - case RL_PIXELFORMAT_UNCOMPRESSED_R16: if (RLGL.ExtSupported.texFloat16) *glInternalFormat = GL_LUMINANCE; *glFormat = GL_LUMINANCE; *glType = GL_HALF_FLOAT_OES; break; // NOTE: Requires extension OES_texture_half_float - case RL_PIXELFORMAT_UNCOMPRESSED_R16G16B16: if (RLGL.ExtSupported.texFloat16) *glInternalFormat = GL_RGB; *glFormat = GL_RGB; *glType = GL_HALF_FLOAT_OES; break; // NOTE: Requires extension OES_texture_half_float - case RL_PIXELFORMAT_UNCOMPRESSED_R16G16B16A16: if (RLGL.ExtSupported.texFloat16) *glInternalFormat = GL_RGBA; *glFormat = GL_RGBA; *glType = GL_HALF_FLOAT_OES; break; // NOTE: Requires extension OES_texture_half_float - #endif - #endif - #endif - #elif defined(GRAPHICS_API_OPENGL_33) - case RL_PIXELFORMAT_UNCOMPRESSED_GRAYSCALE: *glInternalFormat = GL_R8; *glFormat = GL_RED; *glType = GL_UNSIGNED_BYTE; break; - case RL_PIXELFORMAT_UNCOMPRESSED_GRAY_ALPHA: *glInternalFormat = GL_RG8; *glFormat = GL_RG; *glType = GL_UNSIGNED_BYTE; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R5G6B5: *glInternalFormat = GL_RGB565; *glFormat = GL_RGB; *glType = GL_UNSIGNED_SHORT_5_6_5; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R8G8B8: *glInternalFormat = GL_RGB8; *glFormat = GL_RGB; *glType = GL_UNSIGNED_BYTE; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R5G5B5A1: *glInternalFormat = GL_RGB5_A1; *glFormat = GL_RGBA; *glType = GL_UNSIGNED_SHORT_5_5_5_1; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R4G4B4A4: *glInternalFormat = GL_RGBA4; *glFormat = GL_RGBA; *glType = GL_UNSIGNED_SHORT_4_4_4_4; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R8G8B8A8: *glInternalFormat = GL_RGBA8; *glFormat = GL_RGBA; *glType = GL_UNSIGNED_BYTE; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R32: if (RLGL.ExtSupported.texFloat32) *glInternalFormat = GL_R32F; *glFormat = GL_RED; *glType = GL_FLOAT; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R32G32B32: if (RLGL.ExtSupported.texFloat32) *glInternalFormat = GL_RGB32F; *glFormat = GL_RGB; *glType = GL_FLOAT; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R32G32B32A32: if (RLGL.ExtSupported.texFloat32) *glInternalFormat = GL_RGBA32F; *glFormat = GL_RGBA; *glType = GL_FLOAT; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R16: if (RLGL.ExtSupported.texFloat16) *glInternalFormat = GL_R16F; *glFormat = GL_RED; *glType = GL_HALF_FLOAT; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R16G16B16: if (RLGL.ExtSupported.texFloat16) *glInternalFormat = GL_RGB16F; *glFormat = GL_RGB; *glType = GL_HALF_FLOAT; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R16G16B16A16: if (RLGL.ExtSupported.texFloat16) *glInternalFormat = GL_RGBA16F; *glFormat = GL_RGBA; *glType = GL_HALF_FLOAT; break; - #endif - #if !defined(GRAPHICS_API_OPENGL_11) - case RL_PIXELFORMAT_COMPRESSED_DXT1_RGB: if (RLGL.ExtSupported.texCompDXT) *glInternalFormat = GL_COMPRESSED_RGB_S3TC_DXT1_EXT; break; - case RL_PIXELFORMAT_COMPRESSED_DXT1_RGBA: if (RLGL.ExtSupported.texCompDXT) *glInternalFormat = GL_COMPRESSED_RGBA_S3TC_DXT1_EXT; break; - case RL_PIXELFORMAT_COMPRESSED_DXT3_RGBA: if (RLGL.ExtSupported.texCompDXT) *glInternalFormat = GL_COMPRESSED_RGBA_S3TC_DXT3_EXT; break; - case RL_PIXELFORMAT_COMPRESSED_DXT5_RGBA: if (RLGL.ExtSupported.texCompDXT) *glInternalFormat = GL_COMPRESSED_RGBA_S3TC_DXT5_EXT; break; - case RL_PIXELFORMAT_COMPRESSED_ETC1_RGB: if (RLGL.ExtSupported.texCompETC1) *glInternalFormat = GL_ETC1_RGB8_OES; break; // NOTE: Requires OpenGL ES 2.0 or OpenGL 4.3 - case RL_PIXELFORMAT_COMPRESSED_ETC2_RGB: if (RLGL.ExtSupported.texCompETC2) *glInternalFormat = GL_COMPRESSED_RGB8_ETC2; break; // NOTE: Requires OpenGL ES 3.0 or OpenGL 4.3 - case RL_PIXELFORMAT_COMPRESSED_ETC2_EAC_RGBA: if (RLGL.ExtSupported.texCompETC2) *glInternalFormat = GL_COMPRESSED_RGBA8_ETC2_EAC; break; // NOTE: Requires OpenGL ES 3.0 or OpenGL 4.3 - case RL_PIXELFORMAT_COMPRESSED_PVRT_RGB: if (RLGL.ExtSupported.texCompPVRT) *glInternalFormat = GL_COMPRESSED_RGB_PVRTC_4BPPV1_IMG; break; // NOTE: Requires PowerVR GPU - case RL_PIXELFORMAT_COMPRESSED_PVRT_RGBA: if (RLGL.ExtSupported.texCompPVRT) *glInternalFormat = GL_COMPRESSED_RGBA_PVRTC_4BPPV1_IMG; break; // NOTE: Requires PowerVR GPU - case RL_PIXELFORMAT_COMPRESSED_ASTC_4x4_RGBA: if (RLGL.ExtSupported.texCompASTC) *glInternalFormat = GL_COMPRESSED_RGBA_ASTC_4x4_KHR; break; // NOTE: Requires OpenGL ES 3.1 or OpenGL 4.3 - case RL_PIXELFORMAT_COMPRESSED_ASTC_8x8_RGBA: if (RLGL.ExtSupported.texCompASTC) *glInternalFormat = GL_COMPRESSED_RGBA_ASTC_8x8_KHR; break; // NOTE: Requires OpenGL ES 3.1 or OpenGL 4.3 - #endif - default: TRACELOG(RL_LOG_WARNING, "TEXTURE: Current format not supported (%i)", format); break; - } -} - -// Unload texture from GPU memory -void rlUnloadTexture(unsigned int id) -{ - glDeleteTextures(1, &id); -} - -// Generate mipmap data for selected texture -// NOTE: Only supports GPU mipmap generation -void rlGenTextureMipmaps(unsigned int id, int width, int height, int format, int *mipmaps) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - glBindTexture(GL_TEXTURE_2D, id); - - // Check if texture is power-of-two (POT) - bool texIsPOT = false; - - if (((width > 0) && ((width & (width - 1)) == 0)) && - ((height > 0) && ((height & (height - 1)) == 0))) texIsPOT = true; - - if ((texIsPOT) || (RLGL.ExtSupported.texNPOT)) - { - //glHint(GL_GENERATE_MIPMAP_HINT, GL_DONT_CARE); // Hint for mipmaps generation algorithm: GL_FASTEST, GL_NICEST, GL_DONT_CARE - glGenerateMipmap(GL_TEXTURE_2D); // Generate mipmaps automatically - - #define MIN(a,b) (((a)<(b))? (a):(b)) - #define MAX(a,b) (((a)>(b))? (a):(b)) - - *mipmaps = 1 + (int)floor(log(MAX(width, height))/log(2)); - TRACELOG(RL_LOG_INFO, "TEXTURE: [ID %i] Mipmaps generated automatically, total: %i", id, *mipmaps); - } - else TRACELOG(RL_LOG_WARNING, "TEXTURE: [ID %i] Failed to generate mipmaps", id); - - glBindTexture(GL_TEXTURE_2D, 0); -#else - TRACELOG(RL_LOG_WARNING, "TEXTURE: [ID %i] GPU mipmap generation not supported", id); -#endif -} - -// Read texture pixel data -void *rlReadTexturePixels(unsigned int id, int width, int height, int format) -{ - void *pixels = NULL; - -#if defined(GRAPHICS_API_OPENGL_11) || defined(GRAPHICS_API_OPENGL_33) - glBindTexture(GL_TEXTURE_2D, id); - - // NOTE: Using texture id, we can retrieve some texture info (but not on OpenGL ES 2.0) - // Possible texture info: GL_TEXTURE_RED_SIZE, GL_TEXTURE_GREEN_SIZE, GL_TEXTURE_BLUE_SIZE, GL_TEXTURE_ALPHA_SIZE - //int width, height, format; - //glGetTexLevelParameteriv(GL_TEXTURE_2D, 0, GL_TEXTURE_WIDTH, &width); - //glGetTexLevelParameteriv(GL_TEXTURE_2D, 0, GL_TEXTURE_HEIGHT, &height); - //glGetTexLevelParameteriv(GL_TEXTURE_2D, 0, GL_TEXTURE_INTERNAL_FORMAT, &format); - - // NOTE: Each row written to or read from by OpenGL pixel operations like glGetTexImage are aligned to a 4 byte boundary by default, which may add some padding - // Use glPixelStorei to modify padding with the GL_[UN]PACK_ALIGNMENT setting - // GL_PACK_ALIGNMENT affects operations that read from OpenGL memory (glReadPixels, glGetTexImage, etc.) - // GL_UNPACK_ALIGNMENT affects operations that write to OpenGL memory (glTexImage, etc.) - glPixelStorei(GL_PACK_ALIGNMENT, 1); - - unsigned int glInternalFormat, glFormat, glType; - rlGetGlTextureFormats(format, &glInternalFormat, &glFormat, &glType); - unsigned int size = rlGetPixelDataSize(width, height, format); - - if ((glInternalFormat != 0) && (format < RL_PIXELFORMAT_COMPRESSED_DXT1_RGB)) - { - pixels = RL_MALLOC(size); - glGetTexImage(GL_TEXTURE_2D, 0, glFormat, glType, pixels); - } - else TRACELOG(RL_LOG_WARNING, "TEXTURE: [ID %i] Data retrieval not suported for pixel format (%i)", id, format); - - glBindTexture(GL_TEXTURE_2D, 0); -#endif - -#if defined(GRAPHICS_API_OPENGL_ES2) - // glGetTexImage() is not available on OpenGL ES 2.0 - // Texture width and height are required on OpenGL ES 2.0, there is no way to get it from texture id - // Two possible Options: - // 1 - Bind texture to color fbo attachment and glReadPixels() - // 2 - Create an fbo, activate it, render quad with texture, glReadPixels() - // We are using Option 1, just need to care for texture format on retrieval - // NOTE: This behaviour could be conditioned by graphic driver... - unsigned int fboId = rlLoadFramebuffer(); - - glBindFramebuffer(GL_FRAMEBUFFER, fboId); - glBindTexture(GL_TEXTURE_2D, 0); - - // Attach our texture to FBO - glFramebufferTexture2D(GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT0, GL_TEXTURE_2D, id, 0); - - // We read data as RGBA because FBO texture is configured as RGBA, despite binding another texture format - pixels = (unsigned char *)RL_MALLOC(rlGetPixelDataSize(width, height, RL_PIXELFORMAT_UNCOMPRESSED_R8G8B8A8)); - glReadPixels(0, 0, width, height, GL_RGBA, GL_UNSIGNED_BYTE, pixels); - - glBindFramebuffer(GL_FRAMEBUFFER, 0); - - // Clean up temporal fbo - rlUnloadFramebuffer(fboId); -#endif - - return pixels; -} - -// Read screen pixel data (color buffer) -unsigned char *rlReadScreenPixels(int width, int height) -{ - unsigned char *screenData = (unsigned char *)RL_CALLOC(width*height*4, sizeof(unsigned char)); - - // NOTE 1: glReadPixels returns image flipped vertically -> (0,0) is the bottom left corner of the framebuffer - // NOTE 2: We are getting alpha channel! Be careful, it can be transparent if not cleared properly! - glReadPixels(0, 0, width, height, GL_RGBA, GL_UNSIGNED_BYTE, screenData); - - // Flip image vertically! - unsigned char *imgData = (unsigned char *)RL_MALLOC(width*height*4*sizeof(unsigned char)); - - for (int y = height - 1; y >= 0; y--) - { - for (int x = 0; x < (width*4); x++) - { - imgData[((height - 1) - y)*width*4 + x] = screenData[(y*width*4) + x]; // Flip line - - // Set alpha component value to 255 (no trasparent image retrieval) - // NOTE: Alpha value has already been applied to RGB in framebuffer, we don't need it! - if (((x + 1)%4) == 0) imgData[((height - 1) - y)*width*4 + x] = 255; - } - } - - RL_FREE(screenData); - - return imgData; // NOTE: image data should be freed -} - -// Framebuffer management (fbo) -//----------------------------------------------------------------------------------------- -// Load a framebuffer to be used for rendering -// NOTE: No textures attached -unsigned int rlLoadFramebuffer(void) -{ - unsigned int fboId = 0; - -#if (defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2)) && defined(RLGL_RENDER_TEXTURES_HINT) - glGenFramebuffers(1, &fboId); // Create the framebuffer object - glBindFramebuffer(GL_FRAMEBUFFER, 0); // Unbind any framebuffer -#endif - - return fboId; -} - -// Attach color buffer texture to an fbo (unloads previous attachment) -// NOTE: Attach type: 0-Color, 1-Depth renderbuffer, 2-Depth texture -void rlFramebufferAttach(unsigned int fboId, unsigned int texId, int attachType, int texType, int mipLevel) -{ -#if (defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2)) && defined(RLGL_RENDER_TEXTURES_HINT) - glBindFramebuffer(GL_FRAMEBUFFER, fboId); - - switch (attachType) - { - case RL_ATTACHMENT_COLOR_CHANNEL0: - case RL_ATTACHMENT_COLOR_CHANNEL1: - case RL_ATTACHMENT_COLOR_CHANNEL2: - case RL_ATTACHMENT_COLOR_CHANNEL3: - case RL_ATTACHMENT_COLOR_CHANNEL4: - case RL_ATTACHMENT_COLOR_CHANNEL5: - case RL_ATTACHMENT_COLOR_CHANNEL6: - case RL_ATTACHMENT_COLOR_CHANNEL7: - { - if (texType == RL_ATTACHMENT_TEXTURE2D) glFramebufferTexture2D(GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT0 + attachType, GL_TEXTURE_2D, texId, mipLevel); - else if (texType == RL_ATTACHMENT_RENDERBUFFER) glFramebufferRenderbuffer(GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT0 + attachType, GL_RENDERBUFFER, texId); - else if (texType >= RL_ATTACHMENT_CUBEMAP_POSITIVE_X) glFramebufferTexture2D(GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT0 + attachType, GL_TEXTURE_CUBE_MAP_POSITIVE_X + texType, texId, mipLevel); - - } break; - case RL_ATTACHMENT_DEPTH: - { - if (texType == RL_ATTACHMENT_TEXTURE2D) glFramebufferTexture2D(GL_FRAMEBUFFER, GL_DEPTH_ATTACHMENT, GL_TEXTURE_2D, texId, mipLevel); - else if (texType == RL_ATTACHMENT_RENDERBUFFER) glFramebufferRenderbuffer(GL_FRAMEBUFFER, GL_DEPTH_ATTACHMENT, GL_RENDERBUFFER, texId); - - } break; - case RL_ATTACHMENT_STENCIL: - { - if (texType == RL_ATTACHMENT_TEXTURE2D) glFramebufferTexture2D(GL_FRAMEBUFFER, GL_STENCIL_ATTACHMENT, GL_TEXTURE_2D, texId, mipLevel); - else if (texType == RL_ATTACHMENT_RENDERBUFFER) glFramebufferRenderbuffer(GL_FRAMEBUFFER, GL_STENCIL_ATTACHMENT, GL_RENDERBUFFER, texId); - - } break; - default: break; - } - - glBindFramebuffer(GL_FRAMEBUFFER, 0); -#endif -} - -// Verify render texture is complete -bool rlFramebufferComplete(unsigned int id) -{ - bool result = false; - -#if (defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2)) && defined(RLGL_RENDER_TEXTURES_HINT) - glBindFramebuffer(GL_FRAMEBUFFER, id); - - GLenum status = glCheckFramebufferStatus(GL_FRAMEBUFFER); - - if (status != GL_FRAMEBUFFER_COMPLETE) - { - switch (status) - { - case GL_FRAMEBUFFER_UNSUPPORTED: TRACELOG(RL_LOG_WARNING, "FBO: [ID %i] Framebuffer is unsupported", id); break; - case GL_FRAMEBUFFER_INCOMPLETE_ATTACHMENT: TRACELOG(RL_LOG_WARNING, "FBO: [ID %i] Framebuffer has incomplete attachment", id); break; -#if defined(GRAPHICS_API_OPENGL_ES2) - case GL_FRAMEBUFFER_INCOMPLETE_DIMENSIONS: TRACELOG(RL_LOG_WARNING, "FBO: [ID %i] Framebuffer has incomplete dimensions", id); break; -#endif - case GL_FRAMEBUFFER_INCOMPLETE_MISSING_ATTACHMENT: TRACELOG(RL_LOG_WARNING, "FBO: [ID %i] Framebuffer has a missing attachment", id); break; - default: break; - } - } - - glBindFramebuffer(GL_FRAMEBUFFER, 0); - - result = (status == GL_FRAMEBUFFER_COMPLETE); -#endif - - return result; -} - -// Unload framebuffer from GPU memory -// NOTE: All attached textures/cubemaps/renderbuffers are also deleted -void rlUnloadFramebuffer(unsigned int id) -{ -#if (defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2)) && defined(RLGL_RENDER_TEXTURES_HINT) - // Query depth attachment to automatically delete texture/renderbuffer - int depthType = 0, depthId = 0; - glBindFramebuffer(GL_FRAMEBUFFER, id); // Bind framebuffer to query depth texture type - glGetFramebufferAttachmentParameteriv(GL_FRAMEBUFFER, GL_DEPTH_ATTACHMENT, GL_FRAMEBUFFER_ATTACHMENT_OBJECT_TYPE, &depthType); - - // TODO: Review warning retrieving object name in WebGL - // WARNING: WebGL: INVALID_ENUM: getFramebufferAttachmentParameter: invalid parameter name - // https://registry.khronos.org/webgl/specs/latest/1.0/ - glGetFramebufferAttachmentParameteriv(GL_FRAMEBUFFER, GL_DEPTH_ATTACHMENT, GL_FRAMEBUFFER_ATTACHMENT_OBJECT_NAME, &depthId); - - unsigned int depthIdU = (unsigned int)depthId; - if (depthType == GL_RENDERBUFFER) glDeleteRenderbuffers(1, &depthIdU); - else if (depthType == GL_TEXTURE) glDeleteTextures(1, &depthIdU); - - // NOTE: If a texture object is deleted while its image is attached to the *currently bound* framebuffer, - // the texture image is automatically detached from the currently bound framebuffer - - glBindFramebuffer(GL_FRAMEBUFFER, 0); - glDeleteFramebuffers(1, &id); - - TRACELOG(RL_LOG_INFO, "FBO: [ID %i] Unloaded framebuffer from VRAM (GPU)", id); -#endif -} - -// Vertex data management -//----------------------------------------------------------------------------------------- -// Load a new attributes buffer -unsigned int rlLoadVertexBuffer(const void *buffer, int size, bool dynamic) -{ - unsigned int id = 0; - -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - glGenBuffers(1, &id); - glBindBuffer(GL_ARRAY_BUFFER, id); - glBufferData(GL_ARRAY_BUFFER, size, buffer, dynamic? GL_DYNAMIC_DRAW : GL_STATIC_DRAW); -#endif - - return id; -} - -// Load a new attributes element buffer -unsigned int rlLoadVertexBufferElement(const void *buffer, int size, bool dynamic) -{ - unsigned int id = 0; - -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - glGenBuffers(1, &id); - glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, id); - glBufferData(GL_ELEMENT_ARRAY_BUFFER, size, buffer, dynamic? GL_DYNAMIC_DRAW : GL_STATIC_DRAW); -#endif - - return id; -} - -// Enable vertex buffer (VBO) -void rlEnableVertexBuffer(unsigned int id) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - glBindBuffer(GL_ARRAY_BUFFER, id); -#endif -} - -// Disable vertex buffer (VBO) -void rlDisableVertexBuffer(void) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - glBindBuffer(GL_ARRAY_BUFFER, 0); -#endif -} - -// Enable vertex buffer element (VBO element) -void rlEnableVertexBufferElement(unsigned int id) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, id); -#endif -} - -// Disable vertex buffer element (VBO element) -void rlDisableVertexBufferElement(void) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, 0); -#endif -} - -// Update vertex buffer with new data -// NOTE: dataSize and offset must be provided in bytes -void rlUpdateVertexBuffer(unsigned int id, const void *data, int dataSize, int offset) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - glBindBuffer(GL_ARRAY_BUFFER, id); - glBufferSubData(GL_ARRAY_BUFFER, offset, dataSize, data); -#endif -} - -// Update vertex buffer elements with new data -// NOTE: dataSize and offset must be provided in bytes -void rlUpdateVertexBufferElements(unsigned int id, const void *data, int dataSize, int offset) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, id); - glBufferSubData(GL_ELEMENT_ARRAY_BUFFER, offset, dataSize, data); -#endif -} - -// Enable vertex array object (VAO) -bool rlEnableVertexArray(unsigned int vaoId) -{ - bool result = false; -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - if (RLGL.ExtSupported.vao) - { - glBindVertexArray(vaoId); - result = true; - } -#endif - return result; -} - -// Disable vertex array object (VAO) -void rlDisableVertexArray(void) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - if (RLGL.ExtSupported.vao) glBindVertexArray(0); -#endif -} - -// Enable vertex attribute index -void rlEnableVertexAttribute(unsigned int index) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - glEnableVertexAttribArray(index); -#endif -} - -// Disable vertex attribute index -void rlDisableVertexAttribute(unsigned int index) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - glDisableVertexAttribArray(index); -#endif -} - -// Draw vertex array -void rlDrawVertexArray(int offset, int count) -{ - glDrawArrays(GL_TRIANGLES, offset, count); -} - -// Draw vertex array elements -void rlDrawVertexArrayElements(int offset, int count, const void *buffer) -{ - // NOTE: Added pointer math separately from function to avoid UBSAN complaining - unsigned short *bufferPtr = (unsigned short *)buffer; - if (offset > 0) bufferPtr += offset; - - glDrawElements(GL_TRIANGLES, count, GL_UNSIGNED_SHORT, (const unsigned short *)bufferPtr); -} - -// Draw vertex array instanced -void rlDrawVertexArrayInstanced(int offset, int count, int instances) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - glDrawArraysInstanced(GL_TRIANGLES, 0, count, instances); -#endif -} - -// Draw vertex array elements instanced -void rlDrawVertexArrayElementsInstanced(int offset, int count, const void *buffer, int instances) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - // NOTE: Added pointer math separately from function to avoid UBSAN complaining - unsigned short *bufferPtr = (unsigned short *)buffer; - if (offset > 0) bufferPtr += offset; - - glDrawElementsInstanced(GL_TRIANGLES, count, GL_UNSIGNED_SHORT, (const unsigned short *)bufferPtr, instances); -#endif -} - -#if defined(GRAPHICS_API_OPENGL_11) -// Enable vertex state pointer -void rlEnableStatePointer(int vertexAttribType, void *buffer) -{ - if (buffer != NULL) glEnableClientState(vertexAttribType); - switch (vertexAttribType) - { - case GL_VERTEX_ARRAY: glVertexPointer(3, GL_FLOAT, 0, buffer); break; - case GL_TEXTURE_COORD_ARRAY: glTexCoordPointer(2, GL_FLOAT, 0, buffer); break; - case GL_NORMAL_ARRAY: if (buffer != NULL) glNormalPointer(GL_FLOAT, 0, buffer); break; - case GL_COLOR_ARRAY: if (buffer != NULL) glColorPointer(4, GL_UNSIGNED_BYTE, 0, buffer); break; - //case GL_INDEX_ARRAY: if (buffer != NULL) glIndexPointer(GL_SHORT, 0, buffer); break; // Indexed colors - default: break; - } -} - -// Disable vertex state pointer -void rlDisableStatePointer(int vertexAttribType) -{ - glDisableClientState(vertexAttribType); -} -#endif - -// Load vertex array object (VAO) -unsigned int rlLoadVertexArray(void) -{ - unsigned int vaoId = 0; -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - if (RLGL.ExtSupported.vao) - { - glGenVertexArrays(1, &vaoId); - } -#endif - return vaoId; -} - -// Set vertex attribute -void rlSetVertexAttribute(unsigned int index, int compSize, int type, bool normalized, int stride, int offset) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - // NOTE: Data type could be: GL_BYTE, GL_UNSIGNED_BYTE, GL_SHORT, GL_UNSIGNED_SHORT, GL_INT, GL_UNSIGNED_INT - // Additional types (depends on OpenGL version or extensions): - // - GL_HALF_FLOAT, GL_FLOAT, GL_DOUBLE, GL_FIXED, - // - GL_INT_2_10_10_10_REV, GL_UNSIGNED_INT_2_10_10_10_REV, GL_UNSIGNED_INT_10F_11F_11F_REV - - size_t offsetNative = offset; - glVertexAttribPointer(index, compSize, type, normalized, stride, (void *)offsetNative); -#endif -} - -// Set vertex attribute divisor -void rlSetVertexAttributeDivisor(unsigned int index, int divisor) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - glVertexAttribDivisor(index, divisor); -#endif -} - -// Unload vertex array object (VAO) -void rlUnloadVertexArray(unsigned int vaoId) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - if (RLGL.ExtSupported.vao) - { - glBindVertexArray(0); - glDeleteVertexArrays(1, &vaoId); - TRACELOG(RL_LOG_INFO, "VAO: [ID %i] Unloaded vertex array data from VRAM (GPU)", vaoId); - } -#endif -} - -// Unload vertex buffer (VBO) -void rlUnloadVertexBuffer(unsigned int vboId) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - glDeleteBuffers(1, &vboId); - //TRACELOG(RL_LOG_INFO, "VBO: Unloaded vertex data from VRAM (GPU)"); -#endif -} - -// Shaders management -//----------------------------------------------------------------------------------------------- -// Load shader from code strings -// NOTE: If shader string is NULL, using default vertex/fragment shaders -unsigned int rlLoadShaderCode(const char *vsCode, const char *fsCode) -{ - unsigned int id = 0; - -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - unsigned int vertexShaderId = 0; - unsigned int fragmentShaderId = 0; - - // Compile vertex shader (if provided) - // NOTE: If not vertex shader is provided, use default one - if (vsCode != NULL) vertexShaderId = rlCompileShader(vsCode, GL_VERTEX_SHADER); - else vertexShaderId = RLGL.State.defaultVShaderId; - - // Compile fragment shader (if provided) - // NOTE: If not vertex shader is provided, use default one - if (fsCode != NULL) fragmentShaderId = rlCompileShader(fsCode, GL_FRAGMENT_SHADER); - else fragmentShaderId = RLGL.State.defaultFShaderId; - - // In case vertex and fragment shader are the default ones, no need to recompile, we can just assign the default shader program id - if ((vertexShaderId == RLGL.State.defaultVShaderId) && (fragmentShaderId == RLGL.State.defaultFShaderId)) id = RLGL.State.defaultShaderId; - else if ((vertexShaderId > 0) && (fragmentShaderId > 0)) - { - // One of or both shader are new, we need to compile a new shader program - id = rlLoadShaderProgram(vertexShaderId, fragmentShaderId); - - // We can detach and delete vertex/fragment shaders (if not default ones) - // NOTE: We detach shader before deletion to make sure memory is freed - if (vertexShaderId != RLGL.State.defaultVShaderId) - { - // WARNING: Shader program linkage could fail and returned id is 0 - if (id > 0) glDetachShader(id, vertexShaderId); - glDeleteShader(vertexShaderId); - } - if (fragmentShaderId != RLGL.State.defaultFShaderId) - { - // WARNING: Shader program linkage could fail and returned id is 0 - if (id > 0) glDetachShader(id, fragmentShaderId); - glDeleteShader(fragmentShaderId); - } - - // In case shader program loading failed, we assign default shader - if (id == 0) - { - // In case shader loading fails, we return the default shader - TRACELOG(RL_LOG_WARNING, "SHADER: Failed to load custom shader code, using default shader"); - id = RLGL.State.defaultShaderId; - } - /* - else - { - // Get available shader uniforms - // NOTE: This information is useful for debug... - int uniformCount = -1; - glGetProgramiv(id, GL_ACTIVE_UNIFORMS, &uniformCount); - - for (int i = 0; i < uniformCount; i++) - { - int namelen = -1; - int num = -1; - char name[256] = { 0 }; // Assume no variable names longer than 256 - GLenum type = GL_ZERO; - - // Get the name of the uniforms - glGetActiveUniform(id, i, sizeof(name) - 1, &namelen, &num, &type, name); - - name[namelen] = 0; - TRACELOGD("SHADER: [ID %i] Active uniform (%s) set at location: %i", id, name, glGetUniformLocation(id, name)); - } - } - */ - } -#endif - - return id; -} - -// Compile custom shader and return shader id -unsigned int rlCompileShader(const char *shaderCode, int type) -{ - unsigned int shader = 0; - -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - shader = glCreateShader(type); - glShaderSource(shader, 1, &shaderCode, NULL); - - GLint success = 0; - glCompileShader(shader); - glGetShaderiv(shader, GL_COMPILE_STATUS, &success); - - if (success == GL_FALSE) - { - switch (type) - { - case GL_VERTEX_SHADER: TRACELOG(RL_LOG_WARNING, "SHADER: [ID %i] Failed to compile vertex shader code", shader); break; - case GL_FRAGMENT_SHADER: TRACELOG(RL_LOG_WARNING, "SHADER: [ID %i] Failed to compile fragment shader code", shader); break; - //case GL_GEOMETRY_SHADER: - #if defined(GRAPHICS_API_OPENGL_43) - case GL_COMPUTE_SHADER: TRACELOG(RL_LOG_WARNING, "SHADER: [ID %i] Failed to compile compute shader code", shader); break; - #elif defined(GRAPHICS_API_OPENGL_33) - case GL_COMPUTE_SHADER: TRACELOG(RL_LOG_WARNING, "SHADER: Compute shaders not enabled. Define GRAPHICS_API_OPENGL_43", shader); break; - #endif - default: break; - } - - int maxLength = 0; - glGetShaderiv(shader, GL_INFO_LOG_LENGTH, &maxLength); - - if (maxLength > 0) - { - int length = 0; - char *log = (char *)RL_CALLOC(maxLength, sizeof(char)); - glGetShaderInfoLog(shader, maxLength, &length, log); - TRACELOG(RL_LOG_WARNING, "SHADER: [ID %i] Compile error: %s", shader, log); - RL_FREE(log); - } - - shader = 0; - } - else - { - switch (type) - { - case GL_VERTEX_SHADER: TRACELOG(RL_LOG_INFO, "SHADER: [ID %i] Vertex shader compiled successfully", shader); break; - case GL_FRAGMENT_SHADER: TRACELOG(RL_LOG_INFO, "SHADER: [ID %i] Fragment shader compiled successfully", shader); break; - //case GL_GEOMETRY_SHADER: - #if defined(GRAPHICS_API_OPENGL_43) - case GL_COMPUTE_SHADER: TRACELOG(RL_LOG_INFO, "SHADER: [ID %i] Compute shader compiled successfully", shader); break; - #elif defined(GRAPHICS_API_OPENGL_33) - case GL_COMPUTE_SHADER: TRACELOG(RL_LOG_WARNING, "SHADER: Compute shaders not enabled. Define GRAPHICS_API_OPENGL_43", shader); break; - #endif - default: break; - } - } -#endif - - return shader; -} - -// Load custom shader strings and return program id -unsigned int rlLoadShaderProgram(unsigned int vShaderId, unsigned int fShaderId) -{ - unsigned int program = 0; - -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - GLint success = 0; - program = glCreateProgram(); - - glAttachShader(program, vShaderId); - glAttachShader(program, fShaderId); - - // NOTE: Default attribute shader locations must be Bound before linking - glBindAttribLocation(program, RL_DEFAULT_SHADER_ATTRIB_LOCATION_POSITION, RL_DEFAULT_SHADER_ATTRIB_NAME_POSITION); - glBindAttribLocation(program, RL_DEFAULT_SHADER_ATTRIB_LOCATION_TEXCOORD, RL_DEFAULT_SHADER_ATTRIB_NAME_TEXCOORD); - glBindAttribLocation(program, RL_DEFAULT_SHADER_ATTRIB_LOCATION_NORMAL, RL_DEFAULT_SHADER_ATTRIB_NAME_NORMAL); - glBindAttribLocation(program, RL_DEFAULT_SHADER_ATTRIB_LOCATION_COLOR, RL_DEFAULT_SHADER_ATTRIB_NAME_COLOR); - glBindAttribLocation(program, RL_DEFAULT_SHADER_ATTRIB_LOCATION_TANGENT, RL_DEFAULT_SHADER_ATTRIB_NAME_TANGENT); - glBindAttribLocation(program, RL_DEFAULT_SHADER_ATTRIB_LOCATION_TEXCOORD2, RL_DEFAULT_SHADER_ATTRIB_NAME_TEXCOORD2); - -#ifdef RL_SUPPORT_MESH_GPU_SKINNING - glBindAttribLocation(program, RL_DEFAULT_SHADER_ATTRIB_LOCATION_BONEIDS, RL_DEFAULT_SHADER_ATTRIB_NAME_BONEIDS); - glBindAttribLocation(program, RL_DEFAULT_SHADER_ATTRIB_LOCATION_BONEWEIGHTS, RL_DEFAULT_SHADER_ATTRIB_NAME_BONEWEIGHTS); -#endif - - // NOTE: If some attrib name is no found on the shader, it locations becomes -1 - - glLinkProgram(program); - - // NOTE: All uniform variables are intitialised to 0 when a program links - - glGetProgramiv(program, GL_LINK_STATUS, &success); - - if (success == GL_FALSE) - { - TRACELOG(RL_LOG_WARNING, "SHADER: [ID %i] Failed to link shader program", program); - - int maxLength = 0; - glGetProgramiv(program, GL_INFO_LOG_LENGTH, &maxLength); - - if (maxLength > 0) - { - int length = 0; - char *log = (char *)RL_CALLOC(maxLength, sizeof(char)); - glGetProgramInfoLog(program, maxLength, &length, log); - TRACELOG(RL_LOG_WARNING, "SHADER: [ID %i] Link error: %s", program, log); - RL_FREE(log); - } - - glDeleteProgram(program); - - program = 0; - } - else - { - // Get the size of compiled shader program (not available on OpenGL ES 2.0) - // NOTE: If GL_LINK_STATUS is GL_FALSE, program binary length is zero - //GLint binarySize = 0; - //glGetProgramiv(id, GL_PROGRAM_BINARY_LENGTH, &binarySize); - - TRACELOG(RL_LOG_INFO, "SHADER: [ID %i] Program shader loaded successfully", program); - } -#endif - return program; -} - -// Unload shader program -void rlUnloadShaderProgram(unsigned int id) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - glDeleteProgram(id); - - TRACELOG(RL_LOG_INFO, "SHADER: [ID %i] Unloaded shader program data from VRAM (GPU)", id); -#endif -} - -// Get shader location uniform -int rlGetLocationUniform(unsigned int shaderId, const char *uniformName) -{ - int location = -1; -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - location = glGetUniformLocation(shaderId, uniformName); - - //if (location == -1) TRACELOG(RL_LOG_WARNING, "SHADER: [ID %i] Failed to find shader uniform: %s", shaderId, uniformName); - //else TRACELOG(RL_LOG_INFO, "SHADER: [ID %i] Shader uniform (%s) set at location: %i", shaderId, uniformName, location); -#endif - return location; -} - -// Get shader location attribute -int rlGetLocationAttrib(unsigned int shaderId, const char *attribName) -{ - int location = -1; -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - location = glGetAttribLocation(shaderId, attribName); - - //if (location == -1) TRACELOG(RL_LOG_WARNING, "SHADER: [ID %i] Failed to find shader attribute: %s", shaderId, attribName); - //else TRACELOG(RL_LOG_INFO, "SHADER: [ID %i] Shader attribute (%s) set at location: %i", shaderId, attribName, location); -#endif - return location; -} - -// Set shader value uniform -void rlSetUniform(int locIndex, const void *value, int uniformType, int count) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - switch (uniformType) - { - case RL_SHADER_UNIFORM_FLOAT: glUniform1fv(locIndex, count, (float *)value); break; - case RL_SHADER_UNIFORM_VEC2: glUniform2fv(locIndex, count, (float *)value); break; - case RL_SHADER_UNIFORM_VEC3: glUniform3fv(locIndex, count, (float *)value); break; - case RL_SHADER_UNIFORM_VEC4: glUniform4fv(locIndex, count, (float *)value); break; - case RL_SHADER_UNIFORM_INT: glUniform1iv(locIndex, count, (int *)value); break; - case RL_SHADER_UNIFORM_IVEC2: glUniform2iv(locIndex, count, (int *)value); break; - case RL_SHADER_UNIFORM_IVEC3: glUniform3iv(locIndex, count, (int *)value); break; - case RL_SHADER_UNIFORM_IVEC4: glUniform4iv(locIndex, count, (int *)value); break; - #if !defined(GRAPHICS_API_OPENGL_ES2) - case RL_SHADER_UNIFORM_UINT: glUniform1uiv(locIndex, count, (unsigned int *)value); break; - case RL_SHADER_UNIFORM_UIVEC2: glUniform2uiv(locIndex, count, (unsigned int *)value); break; - case RL_SHADER_UNIFORM_UIVEC3: glUniform3uiv(locIndex, count, (unsigned int *)value); break; - case RL_SHADER_UNIFORM_UIVEC4: glUniform4uiv(locIndex, count, (unsigned int *)value); break; - #endif - case RL_SHADER_UNIFORM_SAMPLER2D: glUniform1iv(locIndex, count, (int *)value); break; - default: TRACELOG(RL_LOG_WARNING, "SHADER: Failed to set uniform value, data type not recognized"); - - // TODO: Support glUniform1uiv(), glUniform2uiv(), glUniform3uiv(), glUniform4uiv() - } -#endif -} - -// Set shader value attribute -void rlSetVertexAttributeDefault(int locIndex, const void *value, int attribType, int count) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - switch (attribType) - { - case RL_SHADER_ATTRIB_FLOAT: if (count == 1) glVertexAttrib1fv(locIndex, (float *)value); break; - case RL_SHADER_ATTRIB_VEC2: if (count == 2) glVertexAttrib2fv(locIndex, (float *)value); break; - case RL_SHADER_ATTRIB_VEC3: if (count == 3) glVertexAttrib3fv(locIndex, (float *)value); break; - case RL_SHADER_ATTRIB_VEC4: if (count == 4) glVertexAttrib4fv(locIndex, (float *)value); break; - default: TRACELOG(RL_LOG_WARNING, "SHADER: Failed to set attrib default value, data type not recognized"); - } -#endif -} - -// Set shader value uniform matrix -void rlSetUniformMatrix(int locIndex, Matrix mat) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - float matfloat[16] = { - mat.m0, mat.m1, mat.m2, mat.m3, - mat.m4, mat.m5, mat.m6, mat.m7, - mat.m8, mat.m9, mat.m10, mat.m11, - mat.m12, mat.m13, mat.m14, mat.m15 - }; - glUniformMatrix4fv(locIndex, 1, false, matfloat); -#endif -} - -// Set shader value uniform matrix -void rlSetUniformMatrices(int locIndex, const Matrix *matrices, int count) -{ -#if defined(GRAPHICS_API_OPENGL_33) - glUniformMatrix4fv(locIndex, count, true, (const float *)matrices); -#elif defined(GRAPHICS_API_OPENGL_ES2) - // WARNING: WebGL does not support Matrix transpose ("true" parameter) - // REF: https://developer.mozilla.org/en-US/docs/Web/API/WebGLRenderingContext/uniformMatrix - glUniformMatrix4fv(locIndex, count, false, (const float *)matrices); -#endif -} - -// Set shader value uniform sampler -void rlSetUniformSampler(int locIndex, unsigned int textureId) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - // Check if texture is already active - for (int i = 0; i < RL_DEFAULT_BATCH_MAX_TEXTURE_UNITS; i++) - { - if (RLGL.State.activeTextureId[i] == textureId) - { - glUniform1i(locIndex, 1 + i); - return; - } - } - - // Register a new active texture for the internal batch system - // NOTE: Default texture is always activated as GL_TEXTURE0 - for (int i = 0; i < RL_DEFAULT_BATCH_MAX_TEXTURE_UNITS; i++) - { - if (RLGL.State.activeTextureId[i] == 0) - { - glUniform1i(locIndex, 1 + i); // Activate new texture unit - RLGL.State.activeTextureId[i] = textureId; // Save texture id for binding on drawing - break; - } - } -#endif -} - -// Set shader currently active (id and locations) -void rlSetShader(unsigned int id, int *locs) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - if (RLGL.State.currentShaderId != id) - { - rlDrawRenderBatch(RLGL.currentBatch); - RLGL.State.currentShaderId = id; - RLGL.State.currentShaderLocs = locs; - } -#endif -} - -// Load compute shader program -unsigned int rlLoadComputeShaderProgram(unsigned int shaderId) -{ - unsigned int program = 0; - -#if defined(GRAPHICS_API_OPENGL_43) - GLint success = 0; - program = glCreateProgram(); - glAttachShader(program, shaderId); - glLinkProgram(program); - - // NOTE: All uniform variables are intitialised to 0 when a program links - - glGetProgramiv(program, GL_LINK_STATUS, &success); - - if (success == GL_FALSE) - { - TRACELOG(RL_LOG_WARNING, "SHADER: [ID %i] Failed to link compute shader program", program); - - int maxLength = 0; - glGetProgramiv(program, GL_INFO_LOG_LENGTH, &maxLength); - - if (maxLength > 0) - { - int length = 0; - char *log = (char *)RL_CALLOC(maxLength, sizeof(char)); - glGetProgramInfoLog(program, maxLength, &length, log); - TRACELOG(RL_LOG_WARNING, "SHADER: [ID %i] Link error: %s", program, log); - RL_FREE(log); - } - - glDeleteProgram(program); - - program = 0; - } - else - { - // Get the size of compiled shader program (not available on OpenGL ES 2.0) - // NOTE: If GL_LINK_STATUS is GL_FALSE, program binary length is zero - //GLint binarySize = 0; - //glGetProgramiv(id, GL_PROGRAM_BINARY_LENGTH, &binarySize); - - TRACELOG(RL_LOG_INFO, "SHADER: [ID %i] Compute shader program loaded successfully", program); - } -#else - TRACELOG(RL_LOG_WARNING, "SHADER: Compute shaders not enabled. Define GRAPHICS_API_OPENGL_43"); -#endif - - return program; -} - -// Dispatch compute shader (equivalent to *draw* for graphics pilepine) -void rlComputeShaderDispatch(unsigned int groupX, unsigned int groupY, unsigned int groupZ) -{ -#if defined(GRAPHICS_API_OPENGL_43) - glDispatchCompute(groupX, groupY, groupZ); -#endif -} - -// Load shader storage buffer object (SSBO) -unsigned int rlLoadShaderBuffer(unsigned int size, const void *data, int usageHint) -{ - unsigned int ssbo = 0; - -#if defined(GRAPHICS_API_OPENGL_43) - glGenBuffers(1, &ssbo); - glBindBuffer(GL_SHADER_STORAGE_BUFFER, ssbo); - glBufferData(GL_SHADER_STORAGE_BUFFER, size, data, usageHint? usageHint : RL_STREAM_COPY); - if (data == NULL) glClearBufferData(GL_SHADER_STORAGE_BUFFER, GL_R8UI, GL_RED_INTEGER, GL_UNSIGNED_BYTE, NULL); // Clear buffer data to 0 - glBindBuffer(GL_SHADER_STORAGE_BUFFER, 0); -#else - TRACELOG(RL_LOG_WARNING, "SSBO: SSBO not enabled. Define GRAPHICS_API_OPENGL_43"); -#endif - - return ssbo; -} - -// Unload shader storage buffer object (SSBO) -void rlUnloadShaderBuffer(unsigned int ssboId) -{ -#if defined(GRAPHICS_API_OPENGL_43) - glDeleteBuffers(1, &ssboId); -#else - TRACELOG(RL_LOG_WARNING, "SSBO: SSBO not enabled. Define GRAPHICS_API_OPENGL_43"); -#endif - -} - -// Update SSBO buffer data -void rlUpdateShaderBuffer(unsigned int id, const void *data, unsigned int dataSize, unsigned int offset) -{ -#if defined(GRAPHICS_API_OPENGL_43) - glBindBuffer(GL_SHADER_STORAGE_BUFFER, id); - glBufferSubData(GL_SHADER_STORAGE_BUFFER, offset, dataSize, data); -#endif -} - -// Get SSBO buffer size -unsigned int rlGetShaderBufferSize(unsigned int id) -{ -#if defined(GRAPHICS_API_OPENGL_43) - GLint64 size = 0; - glBindBuffer(GL_SHADER_STORAGE_BUFFER, id); - glGetBufferParameteri64v(GL_SHADER_STORAGE_BUFFER, GL_BUFFER_SIZE, &size); - return (size > 0)? (unsigned int)size : 0; -#else - return 0; -#endif -} - -// Read SSBO buffer data (GPU->CPU) -void rlReadShaderBuffer(unsigned int id, void *dest, unsigned int count, unsigned int offset) -{ -#if defined(GRAPHICS_API_OPENGL_43) - glBindBuffer(GL_SHADER_STORAGE_BUFFER, id); - glGetBufferSubData(GL_SHADER_STORAGE_BUFFER, offset, count, dest); -#endif -} - -// Bind SSBO buffer -void rlBindShaderBuffer(unsigned int id, unsigned int index) -{ -#if defined(GRAPHICS_API_OPENGL_43) - glBindBufferBase(GL_SHADER_STORAGE_BUFFER, index, id); -#endif -} - -// Copy SSBO buffer data -void rlCopyShaderBuffer(unsigned int destId, unsigned int srcId, unsigned int destOffset, unsigned int srcOffset, unsigned int count) -{ -#if defined(GRAPHICS_API_OPENGL_43) - glBindBuffer(GL_COPY_READ_BUFFER, srcId); - glBindBuffer(GL_COPY_WRITE_BUFFER, destId); - glCopyBufferSubData(GL_COPY_READ_BUFFER, GL_COPY_WRITE_BUFFER, srcOffset, destOffset, count); -#endif -} - -// Bind image texture -void rlBindImageTexture(unsigned int id, unsigned int index, int format, bool readonly) -{ -#if defined(GRAPHICS_API_OPENGL_43) - unsigned int glInternalFormat = 0, glFormat = 0, glType = 0; - - rlGetGlTextureFormats(format, &glInternalFormat, &glFormat, &glType); - glBindImageTexture(index, id, 0, 0, 0, readonly? GL_READ_ONLY : GL_READ_WRITE, glInternalFormat); -#else - TRACELOG(RL_LOG_WARNING, "TEXTURE: Image texture binding not enabled. Define GRAPHICS_API_OPENGL_43"); -#endif -} - -// Matrix state management -//----------------------------------------------------------------------------------------- -// Get internal modelview matrix -Matrix rlGetMatrixModelview(void) -{ - Matrix matrix = rlMatrixIdentity(); -#if defined(GRAPHICS_API_OPENGL_11) - float mat[16]; - glGetFloatv(GL_MODELVIEW_MATRIX, mat); - matrix.m0 = mat[0]; - matrix.m1 = mat[1]; - matrix.m2 = mat[2]; - matrix.m3 = mat[3]; - matrix.m4 = mat[4]; - matrix.m5 = mat[5]; - matrix.m6 = mat[6]; - matrix.m7 = mat[7]; - matrix.m8 = mat[8]; - matrix.m9 = mat[9]; - matrix.m10 = mat[10]; - matrix.m11 = mat[11]; - matrix.m12 = mat[12]; - matrix.m13 = mat[13]; - matrix.m14 = mat[14]; - matrix.m15 = mat[15]; -#else - matrix = RLGL.State.modelview; -#endif - return matrix; -} - -// Get internal projection matrix -Matrix rlGetMatrixProjection(void) -{ -#if defined(GRAPHICS_API_OPENGL_11) - float mat[16]; - glGetFloatv(GL_PROJECTION_MATRIX,mat); - Matrix m; - m.m0 = mat[0]; - m.m1 = mat[1]; - m.m2 = mat[2]; - m.m3 = mat[3]; - m.m4 = mat[4]; - m.m5 = mat[5]; - m.m6 = mat[6]; - m.m7 = mat[7]; - m.m8 = mat[8]; - m.m9 = mat[9]; - m.m10 = mat[10]; - m.m11 = mat[11]; - m.m12 = mat[12]; - m.m13 = mat[13]; - m.m14 = mat[14]; - m.m15 = mat[15]; - return m; -#else - return RLGL.State.projection; -#endif -} - -// Get internal accumulated transform matrix -Matrix rlGetMatrixTransform(void) -{ - Matrix mat = rlMatrixIdentity(); -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - // TODO: Consider possible transform matrices in the RLGL.State.stack - // Is this the right order? or should we start with the first stored matrix instead of the last one? - //Matrix matStackTransform = rlMatrixIdentity(); - //for (int i = RLGL.State.stackCounter; i > 0; i--) matStackTransform = rlMatrixMultiply(RLGL.State.stack[i], matStackTransform); - mat = RLGL.State.transform; -#endif - return mat; -} - -// Get internal projection matrix for stereo render (selected eye) -Matrix rlGetMatrixProjectionStereo(int eye) -{ - Matrix mat = rlMatrixIdentity(); -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - mat = RLGL.State.projectionStereo[eye]; -#endif - return mat; -} - -// Get internal view offset matrix for stereo render (selected eye) -Matrix rlGetMatrixViewOffsetStereo(int eye) -{ - Matrix mat = rlMatrixIdentity(); -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - mat = RLGL.State.viewOffsetStereo[eye]; -#endif - return mat; -} - -// Set a custom modelview matrix (replaces internal modelview matrix) -void rlSetMatrixModelview(Matrix view) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - RLGL.State.modelview = view; -#endif -} - -// Set a custom projection matrix (replaces internal projection matrix) -void rlSetMatrixProjection(Matrix projection) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - RLGL.State.projection = projection; -#endif -} - -// Set eyes projection matrices for stereo rendering -void rlSetMatrixProjectionStereo(Matrix right, Matrix left) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - RLGL.State.projectionStereo[0] = right; - RLGL.State.projectionStereo[1] = left; -#endif -} - -// Set eyes view offsets matrices for stereo rendering -void rlSetMatrixViewOffsetStereo(Matrix right, Matrix left) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - RLGL.State.viewOffsetStereo[0] = right; - RLGL.State.viewOffsetStereo[1] = left; -#endif -} - -// Load and draw a quad in NDC -void rlLoadDrawQuad(void) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - unsigned int quadVAO = 0; - unsigned int quadVBO = 0; - - float vertices[] = { - // Positions Texcoords - -1.0f, 1.0f, 0.0f, 0.0f, 1.0f, - -1.0f, -1.0f, 0.0f, 0.0f, 0.0f, - 1.0f, 1.0f, 0.0f, 1.0f, 1.0f, - 1.0f, -1.0f, 0.0f, 1.0f, 0.0f, - }; - - // Gen VAO to contain VBO - glGenVertexArrays(1, &quadVAO); - glBindVertexArray(quadVAO); - - // Gen and fill vertex buffer (VBO) - glGenBuffers(1, &quadVBO); - glBindBuffer(GL_ARRAY_BUFFER, quadVBO); - glBufferData(GL_ARRAY_BUFFER, sizeof(vertices), &vertices, GL_STATIC_DRAW); - - // Bind vertex attributes (position, texcoords) - glEnableVertexAttribArray(RL_DEFAULT_SHADER_ATTRIB_LOCATION_POSITION); - glVertexAttribPointer(RL_DEFAULT_SHADER_ATTRIB_LOCATION_POSITION, 3, GL_FLOAT, GL_FALSE, 5*sizeof(float), (void *)0); // Positions - glEnableVertexAttribArray(RL_DEFAULT_SHADER_ATTRIB_LOCATION_TEXCOORD); - glVertexAttribPointer(RL_DEFAULT_SHADER_ATTRIB_LOCATION_TEXCOORD, 2, GL_FLOAT, GL_FALSE, 5*sizeof(float), (void *)(3*sizeof(float))); // Texcoords - - // Draw quad - glBindVertexArray(quadVAO); - glDrawArrays(GL_TRIANGLE_STRIP, 0, 4); - glBindVertexArray(0); - - // Delete buffers (VBO and VAO) - glDeleteBuffers(1, &quadVBO); - glDeleteVertexArrays(1, &quadVAO); -#endif -} - -// Load and draw a cube in NDC -void rlLoadDrawCube(void) -{ -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) - unsigned int cubeVAO = 0; - unsigned int cubeVBO = 0; - - float vertices[] = { - // Positions Normals Texcoords - -1.0f, -1.0f, -1.0f, 0.0f, 0.0f, -1.0f, 0.0f, 0.0f, - 1.0f, 1.0f, -1.0f, 0.0f, 0.0f, -1.0f, 1.0f, 1.0f, - 1.0f, -1.0f, -1.0f, 0.0f, 0.0f, -1.0f, 1.0f, 0.0f, - 1.0f, 1.0f, -1.0f, 0.0f, 0.0f, -1.0f, 1.0f, 1.0f, - -1.0f, -1.0f, -1.0f, 0.0f, 0.0f, -1.0f, 0.0f, 0.0f, - -1.0f, 1.0f, -1.0f, 0.0f, 0.0f, -1.0f, 0.0f, 1.0f, - -1.0f, -1.0f, 1.0f, 0.0f, 0.0f, 1.0f, 0.0f, 0.0f, - 1.0f, -1.0f, 1.0f, 0.0f, 0.0f, 1.0f, 1.0f, 0.0f, - 1.0f, 1.0f, 1.0f, 0.0f, 0.0f, 1.0f, 1.0f, 1.0f, - 1.0f, 1.0f, 1.0f, 0.0f, 0.0f, 1.0f, 1.0f, 1.0f, - -1.0f, 1.0f, 1.0f, 0.0f, 0.0f, 1.0f, 0.0f, 1.0f, - -1.0f, -1.0f, 1.0f, 0.0f, 0.0f, 1.0f, 0.0f, 0.0f, - -1.0f, 1.0f, 1.0f, -1.0f, 0.0f, 0.0f, 1.0f, 0.0f, - -1.0f, 1.0f, -1.0f, -1.0f, 0.0f, 0.0f, 1.0f, 1.0f, - -1.0f, -1.0f, -1.0f, -1.0f, 0.0f, 0.0f, 0.0f, 1.0f, - -1.0f, -1.0f, -1.0f, -1.0f, 0.0f, 0.0f, 0.0f, 1.0f, - -1.0f, -1.0f, 1.0f, -1.0f, 0.0f, 0.0f, 0.0f, 0.0f, - -1.0f, 1.0f, 1.0f, -1.0f, 0.0f, 0.0f, 1.0f, 0.0f, - 1.0f, 1.0f, 1.0f, 1.0f, 0.0f, 0.0f, 1.0f, 0.0f, - 1.0f, -1.0f, -1.0f, 1.0f, 0.0f, 0.0f, 0.0f, 1.0f, - 1.0f, 1.0f, -1.0f, 1.0f, 0.0f, 0.0f, 1.0f, 1.0f, - 1.0f, -1.0f, -1.0f, 1.0f, 0.0f, 0.0f, 0.0f, 1.0f, - 1.0f, 1.0f, 1.0f, 1.0f, 0.0f, 0.0f, 1.0f, 0.0f, - 1.0f, -1.0f, 1.0f, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, - -1.0f, -1.0f, -1.0f, 0.0f, -1.0f, 0.0f, 0.0f, 1.0f, - 1.0f, -1.0f, -1.0f, 0.0f, -1.0f, 0.0f, 1.0f, 1.0f, - 1.0f, -1.0f, 1.0f, 0.0f, -1.0f, 0.0f, 1.0f, 0.0f, - 1.0f, -1.0f, 1.0f, 0.0f, -1.0f, 0.0f, 1.0f, 0.0f, - -1.0f, -1.0f, 1.0f, 0.0f, -1.0f, 0.0f, 0.0f, 0.0f, - -1.0f, -1.0f, -1.0f, 0.0f, -1.0f, 0.0f, 0.0f, 1.0f, - -1.0f, 1.0f, -1.0f, 0.0f, 1.0f, 0.0f, 0.0f, 1.0f, - 1.0f, 1.0f, 1.0f, 0.0f, 1.0f, 0.0f, 1.0f, 0.0f, - 1.0f, 1.0f, -1.0f, 0.0f, 1.0f, 0.0f, 1.0f, 1.0f, - 1.0f, 1.0f, 1.0f, 0.0f, 1.0f, 0.0f, 1.0f, 0.0f, - -1.0f, 1.0f, -1.0f, 0.0f, 1.0f, 0.0f, 0.0f, 1.0f, - -1.0f, 1.0f, 1.0f, 0.0f, 1.0f, 0.0f, 0.0f, 0.0f - }; - - // Gen VAO to contain VBO - glGenVertexArrays(1, &cubeVAO); - glBindVertexArray(cubeVAO); - - // Gen and fill vertex buffer (VBO) - glGenBuffers(1, &cubeVBO); - glBindBuffer(GL_ARRAY_BUFFER, cubeVBO); - glBufferData(GL_ARRAY_BUFFER, sizeof(vertices), vertices, GL_STATIC_DRAW); - - // Bind vertex attributes (position, normals, texcoords) - glBindVertexArray(cubeVAO); - glEnableVertexAttribArray(RL_DEFAULT_SHADER_ATTRIB_LOCATION_POSITION); - glVertexAttribPointer(RL_DEFAULT_SHADER_ATTRIB_LOCATION_POSITION, 3, GL_FLOAT, GL_FALSE, 8*sizeof(float), (void *)0); // Positions - glEnableVertexAttribArray(RL_DEFAULT_SHADER_ATTRIB_LOCATION_NORMAL); - glVertexAttribPointer(RL_DEFAULT_SHADER_ATTRIB_LOCATION_NORMAL, 3, GL_FLOAT, GL_FALSE, 8*sizeof(float), (void *)(3*sizeof(float))); // Normals - glEnableVertexAttribArray(RL_DEFAULT_SHADER_ATTRIB_LOCATION_TEXCOORD); - glVertexAttribPointer(RL_DEFAULT_SHADER_ATTRIB_LOCATION_TEXCOORD, 2, GL_FLOAT, GL_FALSE, 8*sizeof(float), (void *)(6*sizeof(float))); // Texcoords - glBindBuffer(GL_ARRAY_BUFFER, 0); - glBindVertexArray(0); - - // Draw cube - glBindVertexArray(cubeVAO); - glDrawArrays(GL_TRIANGLES, 0, 36); - glBindVertexArray(0); - - // Delete VBO and VAO - glDeleteBuffers(1, &cubeVBO); - glDeleteVertexArrays(1, &cubeVAO); -#endif -} - -// Get name string for pixel format -const char *rlGetPixelFormatName(unsigned int format) -{ - switch (format) - { - case RL_PIXELFORMAT_UNCOMPRESSED_GRAYSCALE: return "GRAYSCALE"; break; // 8 bit per pixel (no alpha) - case RL_PIXELFORMAT_UNCOMPRESSED_GRAY_ALPHA: return "GRAY_ALPHA"; break; // 8*2 bpp (2 channels) - case RL_PIXELFORMAT_UNCOMPRESSED_R5G6B5: return "R5G6B5"; break; // 16 bpp - case RL_PIXELFORMAT_UNCOMPRESSED_R8G8B8: return "R8G8B8"; break; // 24 bpp - case RL_PIXELFORMAT_UNCOMPRESSED_R5G5B5A1: return "R5G5B5A1"; break; // 16 bpp (1 bit alpha) - case RL_PIXELFORMAT_UNCOMPRESSED_R4G4B4A4: return "R4G4B4A4"; break; // 16 bpp (4 bit alpha) - case RL_PIXELFORMAT_UNCOMPRESSED_R8G8B8A8: return "R8G8B8A8"; break; // 32 bpp - case RL_PIXELFORMAT_UNCOMPRESSED_R32: return "R32"; break; // 32 bpp (1 channel - float) - case RL_PIXELFORMAT_UNCOMPRESSED_R32G32B32: return "R32G32B32"; break; // 32*3 bpp (3 channels - float) - case RL_PIXELFORMAT_UNCOMPRESSED_R32G32B32A32: return "R32G32B32A32"; break; // 32*4 bpp (4 channels - float) - case RL_PIXELFORMAT_UNCOMPRESSED_R16: return "R16"; break; // 16 bpp (1 channel - half float) - case RL_PIXELFORMAT_UNCOMPRESSED_R16G16B16: return "R16G16B16"; break; // 16*3 bpp (3 channels - half float) - case RL_PIXELFORMAT_UNCOMPRESSED_R16G16B16A16: return "R16G16B16A16"; break; // 16*4 bpp (4 channels - half float) - case RL_PIXELFORMAT_COMPRESSED_DXT1_RGB: return "DXT1_RGB"; break; // 4 bpp (no alpha) - case RL_PIXELFORMAT_COMPRESSED_DXT1_RGBA: return "DXT1_RGBA"; break; // 4 bpp (1 bit alpha) - case RL_PIXELFORMAT_COMPRESSED_DXT3_RGBA: return "DXT3_RGBA"; break; // 8 bpp - case RL_PIXELFORMAT_COMPRESSED_DXT5_RGBA: return "DXT5_RGBA"; break; // 8 bpp - case RL_PIXELFORMAT_COMPRESSED_ETC1_RGB: return "ETC1_RGB"; break; // 4 bpp - case RL_PIXELFORMAT_COMPRESSED_ETC2_RGB: return "ETC2_RGB"; break; // 4 bpp - case RL_PIXELFORMAT_COMPRESSED_ETC2_EAC_RGBA: return "ETC2_RGBA"; break; // 8 bpp - case RL_PIXELFORMAT_COMPRESSED_PVRT_RGB: return "PVRT_RGB"; break; // 4 bpp - case RL_PIXELFORMAT_COMPRESSED_PVRT_RGBA: return "PVRT_RGBA"; break; // 4 bpp - case RL_PIXELFORMAT_COMPRESSED_ASTC_4x4_RGBA: return "ASTC_4x4_RGBA"; break; // 8 bpp - case RL_PIXELFORMAT_COMPRESSED_ASTC_8x8_RGBA: return "ASTC_8x8_RGBA"; break; // 2 bpp - default: return "UNKNOWN"; break; - } -} - -//---------------------------------------------------------------------------------- -// Module specific Functions Definition -//---------------------------------------------------------------------------------- -#if defined(GRAPHICS_API_OPENGL_33) || defined(GRAPHICS_API_OPENGL_ES2) -// Load default shader (just vertex positioning and texture coloring) -// NOTE: This shader program is used for internal buffers -// NOTE: Loaded: RLGL.State.defaultShaderId, RLGL.State.defaultShaderLocs -static void rlLoadShaderDefault(void) -{ - RLGL.State.defaultShaderLocs = (int *)RL_CALLOC(RL_MAX_SHADER_LOCATIONS, sizeof(int)); - - // NOTE: All locations must be reseted to -1 (no location) - for (int i = 0; i < RL_MAX_SHADER_LOCATIONS; i++) RLGL.State.defaultShaderLocs[i] = -1; - - // Vertex shader directly defined, no external file required - const char *defaultVShaderCode = -#if defined(GRAPHICS_API_OPENGL_21) - "#version 120 \n" - "attribute vec3 vertexPosition; \n" - "attribute vec2 vertexTexCoord; \n" - "attribute vec4 vertexColor; \n" - "varying vec2 fragTexCoord; \n" - "varying vec4 fragColor; \n" -#elif defined(GRAPHICS_API_OPENGL_33) - "#version 330 \n" - "in vec3 vertexPosition; \n" - "in vec2 vertexTexCoord; \n" - "in vec4 vertexColor; \n" - "out vec2 fragTexCoord; \n" - "out vec4 fragColor; \n" -#endif - -#if defined(GRAPHICS_API_OPENGL_ES3) - "#version 300 es \n" - "precision mediump float; \n" // Precision required for OpenGL ES3 (WebGL 2) (on some browsers) - "in vec3 vertexPosition; \n" - "in vec2 vertexTexCoord; \n" - "in vec4 vertexColor; \n" - "out vec2 fragTexCoord; \n" - "out vec4 fragColor; \n" -#elif defined(GRAPHICS_API_OPENGL_ES2) - "#version 100 \n" - "precision mediump float; \n" // Precision required for OpenGL ES2 (WebGL) (on some browsers) - "attribute vec3 vertexPosition; \n" - "attribute vec2 vertexTexCoord; \n" - "attribute vec4 vertexColor; \n" - "varying vec2 fragTexCoord; \n" - "varying vec4 fragColor; \n" -#endif - - "uniform mat4 mvp; \n" - "void main() \n" - "{ \n" - " fragTexCoord = vertexTexCoord; \n" - " fragColor = vertexColor; \n" - " gl_Position = mvp*vec4(vertexPosition, 1.0); \n" - "} \n"; - - // Fragment shader directly defined, no external file required - const char *defaultFShaderCode = -#if defined(GRAPHICS_API_OPENGL_21) - "#version 120 \n" - "varying vec2 fragTexCoord; \n" - "varying vec4 fragColor; \n" - "uniform sampler2D texture0; \n" - "uniform vec4 colDiffuse; \n" - "void main() \n" - "{ \n" - " vec4 texelColor = texture2D(texture0, fragTexCoord); \n" - " gl_FragColor = texelColor*colDiffuse*fragColor; \n" - "} \n"; -#elif defined(GRAPHICS_API_OPENGL_33) - "#version 330 \n" - "in vec2 fragTexCoord; \n" - "in vec4 fragColor; \n" - "out vec4 finalColor; \n" - "uniform sampler2D texture0; \n" - "uniform vec4 colDiffuse; \n" - "void main() \n" - "{ \n" - " vec4 texelColor = texture(texture0, fragTexCoord); \n" - " finalColor = texelColor*colDiffuse*fragColor; \n" - "} \n"; -#endif - -#if defined(GRAPHICS_API_OPENGL_ES3) - "#version 300 es \n" - "precision mediump float; \n" // Precision required for OpenGL ES3 (WebGL 2) - "in vec2 fragTexCoord; \n" - "in vec4 fragColor; \n" - "out vec4 finalColor; \n" - "uniform sampler2D texture0; \n" - "uniform vec4 colDiffuse; \n" - "void main() \n" - "{ \n" - " vec4 texelColor = texture(texture0, fragTexCoord); \n" - " finalColor = texelColor*colDiffuse*fragColor; \n" - "} \n"; -#elif defined(GRAPHICS_API_OPENGL_ES2) - "#version 100 \n" - "precision mediump float; \n" // Precision required for OpenGL ES2 (WebGL) - "varying vec2 fragTexCoord; \n" - "varying vec4 fragColor; \n" - "uniform sampler2D texture0; \n" - "uniform vec4 colDiffuse; \n" - "void main() \n" - "{ \n" - " vec4 texelColor = texture2D(texture0, fragTexCoord); \n" - " gl_FragColor = texelColor*colDiffuse*fragColor; \n" - "} \n"; -#endif - - // NOTE: Compiled vertex/fragment shaders are not deleted, - // they are kept for re-use as default shaders in case some shader loading fails - RLGL.State.defaultVShaderId = rlCompileShader(defaultVShaderCode, GL_VERTEX_SHADER); // Compile default vertex shader - RLGL.State.defaultFShaderId = rlCompileShader(defaultFShaderCode, GL_FRAGMENT_SHADER); // Compile default fragment shader - - RLGL.State.defaultShaderId = rlLoadShaderProgram(RLGL.State.defaultVShaderId, RLGL.State.defaultFShaderId); - - if (RLGL.State.defaultShaderId > 0) - { - TRACELOG(RL_LOG_INFO, "SHADER: [ID %i] Default shader loaded successfully", RLGL.State.defaultShaderId); - - // Set default shader locations: attributes locations - RLGL.State.defaultShaderLocs[RL_SHADER_LOC_VERTEX_POSITION] = glGetAttribLocation(RLGL.State.defaultShaderId, RL_DEFAULT_SHADER_ATTRIB_NAME_POSITION); - RLGL.State.defaultShaderLocs[RL_SHADER_LOC_VERTEX_TEXCOORD01] = glGetAttribLocation(RLGL.State.defaultShaderId, RL_DEFAULT_SHADER_ATTRIB_NAME_TEXCOORD); - RLGL.State.defaultShaderLocs[RL_SHADER_LOC_VERTEX_COLOR] = glGetAttribLocation(RLGL.State.defaultShaderId, RL_DEFAULT_SHADER_ATTRIB_NAME_COLOR); - - // Set default shader locations: uniform locations - RLGL.State.defaultShaderLocs[RL_SHADER_LOC_MATRIX_MVP] = glGetUniformLocation(RLGL.State.defaultShaderId, RL_DEFAULT_SHADER_UNIFORM_NAME_MVP); - RLGL.State.defaultShaderLocs[RL_SHADER_LOC_COLOR_DIFFUSE] = glGetUniformLocation(RLGL.State.defaultShaderId, RL_DEFAULT_SHADER_UNIFORM_NAME_COLOR); - RLGL.State.defaultShaderLocs[RL_SHADER_LOC_MAP_DIFFUSE] = glGetUniformLocation(RLGL.State.defaultShaderId, RL_DEFAULT_SHADER_SAMPLER2D_NAME_TEXTURE0); - } - else TRACELOG(RL_LOG_WARNING, "SHADER: [ID %i] Failed to load default shader", RLGL.State.defaultShaderId); -} - -// Unload default shader -// NOTE: Unloads: RLGL.State.defaultShaderId, RLGL.State.defaultShaderLocs -static void rlUnloadShaderDefault(void) -{ - glUseProgram(0); - - glDetachShader(RLGL.State.defaultShaderId, RLGL.State.defaultVShaderId); - glDetachShader(RLGL.State.defaultShaderId, RLGL.State.defaultFShaderId); - glDeleteShader(RLGL.State.defaultVShaderId); - glDeleteShader(RLGL.State.defaultFShaderId); - - glDeleteProgram(RLGL.State.defaultShaderId); - - RL_FREE(RLGL.State.defaultShaderLocs); - - TRACELOG(RL_LOG_INFO, "SHADER: [ID %i] Default shader unloaded successfully", RLGL.State.defaultShaderId); -} - -#if defined(RLGL_SHOW_GL_DETAILS_INFO) -// Get compressed format official GL identifier name -static const char *rlGetCompressedFormatName(int format) -{ - switch (format) - { - // GL_EXT_texture_compression_s3tc - case 0x83F0: return "GL_COMPRESSED_RGB_S3TC_DXT1_EXT"; break; - case 0x83F1: return "GL_COMPRESSED_RGBA_S3TC_DXT1_EXT"; break; - case 0x83F2: return "GL_COMPRESSED_RGBA_S3TC_DXT3_EXT"; break; - case 0x83F3: return "GL_COMPRESSED_RGBA_S3TC_DXT5_EXT"; break; - // GL_3DFX_texture_compression_FXT1 - case 0x86B0: return "GL_COMPRESSED_RGB_FXT1_3DFX"; break; - case 0x86B1: return "GL_COMPRESSED_RGBA_FXT1_3DFX"; break; - // GL_IMG_texture_compression_pvrtc - case 0x8C00: return "GL_COMPRESSED_RGB_PVRTC_4BPPV1_IMG"; break; - case 0x8C01: return "GL_COMPRESSED_RGB_PVRTC_2BPPV1_IMG"; break; - case 0x8C02: return "GL_COMPRESSED_RGBA_PVRTC_4BPPV1_IMG"; break; - case 0x8C03: return "GL_COMPRESSED_RGBA_PVRTC_2BPPV1_IMG"; break; - // GL_OES_compressed_ETC1_RGB8_texture - case 0x8D64: return "GL_ETC1_RGB8_OES"; break; - // GL_ARB_texture_compression_rgtc - case 0x8DBB: return "GL_COMPRESSED_RED_RGTC1"; break; - case 0x8DBC: return "GL_COMPRESSED_SIGNED_RED_RGTC1"; break; - case 0x8DBD: return "GL_COMPRESSED_RG_RGTC2"; break; - case 0x8DBE: return "GL_COMPRESSED_SIGNED_RG_RGTC2"; break; - // GL_ARB_texture_compression_bptc - case 0x8E8C: return "GL_COMPRESSED_RGBA_BPTC_UNORM_ARB"; break; - case 0x8E8D: return "GL_COMPRESSED_SRGB_ALPHA_BPTC_UNORM_ARB"; break; - case 0x8E8E: return "GL_COMPRESSED_RGB_BPTC_SIGNED_FLOAT_ARB"; break; - case 0x8E8F: return "GL_COMPRESSED_RGB_BPTC_UNSIGNED_FLOAT_ARB"; break; - // GL_ARB_ES3_compatibility - case 0x9274: return "GL_COMPRESSED_RGB8_ETC2"; break; - case 0x9275: return "GL_COMPRESSED_SRGB8_ETC2"; break; - case 0x9276: return "GL_COMPRESSED_RGB8_PUNCHTHROUGH_ALPHA1_ETC2"; break; - case 0x9277: return "GL_COMPRESSED_SRGB8_PUNCHTHROUGH_ALPHA1_ETC2"; break; - case 0x9278: return "GL_COMPRESSED_RGBA8_ETC2_EAC"; break; - case 0x9279: return "GL_COMPRESSED_SRGB8_ALPHA8_ETC2_EAC"; break; - case 0x9270: return "GL_COMPRESSED_R11_EAC"; break; - case 0x9271: return "GL_COMPRESSED_SIGNED_R11_EAC"; break; - case 0x9272: return "GL_COMPRESSED_RG11_EAC"; break; - case 0x9273: return "GL_COMPRESSED_SIGNED_RG11_EAC"; break; - // GL_KHR_texture_compression_astc_hdr - case 0x93B0: return "GL_COMPRESSED_RGBA_ASTC_4x4_KHR"; break; - case 0x93B1: return "GL_COMPRESSED_RGBA_ASTC_5x4_KHR"; break; - case 0x93B2: return "GL_COMPRESSED_RGBA_ASTC_5x5_KHR"; break; - case 0x93B3: return "GL_COMPRESSED_RGBA_ASTC_6x5_KHR"; break; - case 0x93B4: return "GL_COMPRESSED_RGBA_ASTC_6x6_KHR"; break; - case 0x93B5: return "GL_COMPRESSED_RGBA_ASTC_8x5_KHR"; break; - case 0x93B6: return "GL_COMPRESSED_RGBA_ASTC_8x6_KHR"; break; - case 0x93B7: return "GL_COMPRESSED_RGBA_ASTC_8x8_KHR"; break; - case 0x93B8: return "GL_COMPRESSED_RGBA_ASTC_10x5_KHR"; break; - case 0x93B9: return "GL_COMPRESSED_RGBA_ASTC_10x6_KHR"; break; - case 0x93BA: return "GL_COMPRESSED_RGBA_ASTC_10x8_KHR"; break; - case 0x93BB: return "GL_COMPRESSED_RGBA_ASTC_10x10_KHR"; break; - case 0x93BC: return "GL_COMPRESSED_RGBA_ASTC_12x10_KHR"; break; - case 0x93BD: return "GL_COMPRESSED_RGBA_ASTC_12x12_KHR"; break; - case 0x93D0: return "GL_COMPRESSED_SRGB8_ALPHA8_ASTC_4x4_KHR"; break; - case 0x93D1: return "GL_COMPRESSED_SRGB8_ALPHA8_ASTC_5x4_KHR"; break; - case 0x93D2: return "GL_COMPRESSED_SRGB8_ALPHA8_ASTC_5x5_KHR"; break; - case 0x93D3: return "GL_COMPRESSED_SRGB8_ALPHA8_ASTC_6x5_KHR"; break; - case 0x93D4: return "GL_COMPRESSED_SRGB8_ALPHA8_ASTC_6x6_KHR"; break; - case 0x93D5: return "GL_COMPRESSED_SRGB8_ALPHA8_ASTC_8x5_KHR"; break; - case 0x93D6: return "GL_COMPRESSED_SRGB8_ALPHA8_ASTC_8x6_KHR"; break; - case 0x93D7: return "GL_COMPRESSED_SRGB8_ALPHA8_ASTC_8x8_KHR"; break; - case 0x93D8: return "GL_COMPRESSED_SRGB8_ALPHA8_ASTC_10x5_KHR"; break; - case 0x93D9: return "GL_COMPRESSED_SRGB8_ALPHA8_ASTC_10x6_KHR"; break; - case 0x93DA: return "GL_COMPRESSED_SRGB8_ALPHA8_ASTC_10x8_KHR"; break; - case 0x93DB: return "GL_COMPRESSED_SRGB8_ALPHA8_ASTC_10x10_KHR"; break; - case 0x93DC: return "GL_COMPRESSED_SRGB8_ALPHA8_ASTC_12x10_KHR"; break; - case 0x93DD: return "GL_COMPRESSED_SRGB8_ALPHA8_ASTC_12x12_KHR"; break; - default: return "GL_COMPRESSED_UNKNOWN"; break; - } -} -#endif // RLGL_SHOW_GL_DETAILS_INFO - -#endif // GRAPHICS_API_OPENGL_33 || GRAPHICS_API_OPENGL_ES2 - -// Get pixel data size in bytes (image or texture) -// NOTE: Size depends on pixel format -static int rlGetPixelDataSize(int width, int height, int format) -{ - int dataSize = 0; // Size in bytes - int bpp = 0; // Bits per pixel - - switch (format) - { - case RL_PIXELFORMAT_UNCOMPRESSED_GRAYSCALE: bpp = 8; break; - case RL_PIXELFORMAT_UNCOMPRESSED_GRAY_ALPHA: - case RL_PIXELFORMAT_UNCOMPRESSED_R5G6B5: - case RL_PIXELFORMAT_UNCOMPRESSED_R5G5B5A1: - case RL_PIXELFORMAT_UNCOMPRESSED_R4G4B4A4: bpp = 16; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R8G8B8A8: bpp = 32; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R8G8B8: bpp = 24; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R32: bpp = 32; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R32G32B32: bpp = 32*3; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R32G32B32A32: bpp = 32*4; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R16: bpp = 16; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R16G16B16: bpp = 16*3; break; - case RL_PIXELFORMAT_UNCOMPRESSED_R16G16B16A16: bpp = 16*4; break; - case RL_PIXELFORMAT_COMPRESSED_DXT1_RGB: - case RL_PIXELFORMAT_COMPRESSED_DXT1_RGBA: - case RL_PIXELFORMAT_COMPRESSED_ETC1_RGB: - case RL_PIXELFORMAT_COMPRESSED_ETC2_RGB: - case RL_PIXELFORMAT_COMPRESSED_PVRT_RGB: - case RL_PIXELFORMAT_COMPRESSED_PVRT_RGBA: bpp = 4; break; - case RL_PIXELFORMAT_COMPRESSED_DXT3_RGBA: - case RL_PIXELFORMAT_COMPRESSED_DXT5_RGBA: - case RL_PIXELFORMAT_COMPRESSED_ETC2_EAC_RGBA: - case RL_PIXELFORMAT_COMPRESSED_ASTC_4x4_RGBA: bpp = 8; break; - case RL_PIXELFORMAT_COMPRESSED_ASTC_8x8_RGBA: bpp = 2; break; - default: break; - } - - double bytesPerPixel = (double)bpp/8.0; - dataSize = (int)(bytesPerPixel*width*height); // Total data size in bytes - - // Most compressed formats works on 4x4 blocks, - // if texture is smaller, minimum dataSize is 8 or 16 - if ((width < 4) && (height < 4)) - { - if ((format >= RL_PIXELFORMAT_COMPRESSED_DXT1_RGB) && (format < RL_PIXELFORMAT_COMPRESSED_DXT3_RGBA)) dataSize = 8; - else if ((format >= RL_PIXELFORMAT_COMPRESSED_DXT3_RGBA) && (format < RL_PIXELFORMAT_COMPRESSED_ASTC_8x8_RGBA)) dataSize = 16; - } - - return dataSize; -} - -// Auxiliar math functions - -// Get float array of matrix data -static rl_float16 rlMatrixToFloatV(Matrix mat) -{ - rl_float16 result = { 0 }; - - result.v[0] = mat.m0; - result.v[1] = mat.m1; - result.v[2] = mat.m2; - result.v[3] = mat.m3; - result.v[4] = mat.m4; - result.v[5] = mat.m5; - result.v[6] = mat.m6; - result.v[7] = mat.m7; - result.v[8] = mat.m8; - result.v[9] = mat.m9; - result.v[10] = mat.m10; - result.v[11] = mat.m11; - result.v[12] = mat.m12; - result.v[13] = mat.m13; - result.v[14] = mat.m14; - result.v[15] = mat.m15; - - return result; -} - -// Get identity matrix -static Matrix rlMatrixIdentity(void) -{ - Matrix result = { - 1.0f, 0.0f, 0.0f, 0.0f, - 0.0f, 1.0f, 0.0f, 0.0f, - 0.0f, 0.0f, 1.0f, 0.0f, - 0.0f, 0.0f, 0.0f, 1.0f - }; - - return result; -} - -// Get two matrix multiplication -// NOTE: When multiplying matrices... the order matters! -static Matrix rlMatrixMultiply(Matrix left, Matrix right) -{ - Matrix result = { 0 }; - - result.m0 = left.m0*right.m0 + left.m1*right.m4 + left.m2*right.m8 + left.m3*right.m12; - result.m1 = left.m0*right.m1 + left.m1*right.m5 + left.m2*right.m9 + left.m3*right.m13; - result.m2 = left.m0*right.m2 + left.m1*right.m6 + left.m2*right.m10 + left.m3*right.m14; - result.m3 = left.m0*right.m3 + left.m1*right.m7 + left.m2*right.m11 + left.m3*right.m15; - result.m4 = left.m4*right.m0 + left.m5*right.m4 + left.m6*right.m8 + left.m7*right.m12; - result.m5 = left.m4*right.m1 + left.m5*right.m5 + left.m6*right.m9 + left.m7*right.m13; - result.m6 = left.m4*right.m2 + left.m5*right.m6 + left.m6*right.m10 + left.m7*right.m14; - result.m7 = left.m4*right.m3 + left.m5*right.m7 + left.m6*right.m11 + left.m7*right.m15; - result.m8 = left.m8*right.m0 + left.m9*right.m4 + left.m10*right.m8 + left.m11*right.m12; - result.m9 = left.m8*right.m1 + left.m9*right.m5 + left.m10*right.m9 + left.m11*right.m13; - result.m10 = left.m8*right.m2 + left.m9*right.m6 + left.m10*right.m10 + left.m11*right.m14; - result.m11 = left.m8*right.m3 + left.m9*right.m7 + left.m10*right.m11 + left.m11*right.m15; - result.m12 = left.m12*right.m0 + left.m13*right.m4 + left.m14*right.m8 + left.m15*right.m12; - result.m13 = left.m12*right.m1 + left.m13*right.m5 + left.m14*right.m9 + left.m15*right.m13; - result.m14 = left.m12*right.m2 + left.m13*right.m6 + left.m14*right.m10 + left.m15*right.m14; - result.m15 = left.m12*right.m3 + left.m13*right.m7 + left.m14*right.m11 + left.m15*right.m15; - - return result; -} - -// Transposes provided matrix -static Matrix rlMatrixTranspose(Matrix mat) -{ - Matrix result = { 0 }; - - result.m0 = mat.m0; - result.m1 = mat.m4; - result.m2 = mat.m8; - result.m3 = mat.m12; - result.m4 = mat.m1; - result.m5 = mat.m5; - result.m6 = mat.m9; - result.m7 = mat.m13; - result.m8 = mat.m2; - result.m9 = mat.m6; - result.m10 = mat.m10; - result.m11 = mat.m14; - result.m12 = mat.m3; - result.m13 = mat.m7; - result.m14 = mat.m11; - result.m15 = mat.m15; - - return result; -} - -// Invert provided matrix -static Matrix rlMatrixInvert(Matrix mat) -{ - Matrix result = { 0 }; - - // Cache the matrix values (speed optimization) - float a00 = mat.m0, a01 = mat.m1, a02 = mat.m2, a03 = mat.m3; - float a10 = mat.m4, a11 = mat.m5, a12 = mat.m6, a13 = mat.m7; - float a20 = mat.m8, a21 = mat.m9, a22 = mat.m10, a23 = mat.m11; - float a30 = mat.m12, a31 = mat.m13, a32 = mat.m14, a33 = mat.m15; - - float b00 = a00*a11 - a01*a10; - float b01 = a00*a12 - a02*a10; - float b02 = a00*a13 - a03*a10; - float b03 = a01*a12 - a02*a11; - float b04 = a01*a13 - a03*a11; - float b05 = a02*a13 - a03*a12; - float b06 = a20*a31 - a21*a30; - float b07 = a20*a32 - a22*a30; - float b08 = a20*a33 - a23*a30; - float b09 = a21*a32 - a22*a31; - float b10 = a21*a33 - a23*a31; - float b11 = a22*a33 - a23*a32; - - // Calculate the invert determinant (inlined to avoid double-caching) - float invDet = 1.0f/(b00*b11 - b01*b10 + b02*b09 + b03*b08 - b04*b07 + b05*b06); - - result.m0 = (a11*b11 - a12*b10 + a13*b09)*invDet; - result.m1 = (-a01*b11 + a02*b10 - a03*b09)*invDet; - result.m2 = (a31*b05 - a32*b04 + a33*b03)*invDet; - result.m3 = (-a21*b05 + a22*b04 - a23*b03)*invDet; - result.m4 = (-a10*b11 + a12*b08 - a13*b07)*invDet; - result.m5 = (a00*b11 - a02*b08 + a03*b07)*invDet; - result.m6 = (-a30*b05 + a32*b02 - a33*b01)*invDet; - result.m7 = (a20*b05 - a22*b02 + a23*b01)*invDet; - result.m8 = (a10*b10 - a11*b08 + a13*b06)*invDet; - result.m9 = (-a00*b10 + a01*b08 - a03*b06)*invDet; - result.m10 = (a30*b04 - a31*b02 + a33*b00)*invDet; - result.m11 = (-a20*b04 + a21*b02 - a23*b00)*invDet; - result.m12 = (-a10*b09 + a11*b07 - a12*b06)*invDet; - result.m13 = (a00*b09 - a01*b07 + a02*b06)*invDet; - result.m14 = (-a30*b03 + a31*b01 - a32*b00)*invDet; - result.m15 = (a20*b03 - a21*b01 + a22*b00)*invDet; - - return result; -} - -#endif // RLGL_IMPLEMENTATION diff --git a/third_party/raylib/larch64/libraylib.a b/third_party/raylib/larch64/libraylib.a deleted file mode 100644 index fa538e5214..0000000000 --- a/third_party/raylib/larch64/libraylib.a +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:f760af8b4693cf60e3760341e5275890d78d933da2354c4bad0572ec575b970a -size 2001860 diff --git a/third_party/raylib/x86_64/libraylib.a b/third_party/raylib/x86_64/libraylib.a deleted file mode 100644 index ea124c1bcf..0000000000 --- a/third_party/raylib/x86_64/libraylib.a +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:3c928e849b51b04d8e3603cd649184299efed0e9e0fb02201612b967b31efd73 -size 2771092 diff --git a/tinygrad_repo b/tinygrad_repo index 3501a71478..ac1632ab96 160000 --- a/tinygrad_repo +++ b/tinygrad_repo @@ -1 +1 @@ -Subproject commit 3501a714785ff370cffb966a45d5f9cdf6c9ea7a +Subproject commit ac1632ab966c77ba96a7048b893a30f1a714dc87 diff --git a/tools/README.md b/tools/README.md index 90696ab4e6..1ea42bbe1d 100644 --- a/tools/README.md +++ b/tools/README.md @@ -29,7 +29,7 @@ source .venv/bin/activate **4. Build openpilot** ``` bash -scons -u -j$(nproc) +scons -u ``` ## WSL on Windows diff --git a/tools/bodyteleop/web.py b/tools/bodyteleop/web.py index f91d6a1441..d357561b22 100644 --- a/tools/bodyteleop/web.py +++ b/tools/bodyteleop/web.py @@ -56,7 +56,7 @@ async def ping(request: 'web.Request'): async def offer(request: 'web.Request'): params = await request.json() - body = StreamRequestBody(params["sdp"], ["driver"], ["testJoystick"], ["carState"]) + body = StreamRequestBody(params["sdp"], "driver", ["testJoystick"], ["carState"]) body_json = json.dumps(dataclasses.asdict(body)) logger.info("Sending offer to webrtcd...") @@ -69,7 +69,7 @@ async def offer(request: 'web.Request'): def main(): # Enable joystick debug mode - Params().put_bool("JoystickDebugMode", True) + Params().put_bool("JoystickDebugMode", True, block=True) # App needs to be HTTPS for WebRTC to work on the browser ssl_context = create_ssl_context() diff --git a/tools/cabana/.gitignore b/tools/cabana/.gitignore index 1ee6c92236..927b05e34a 100644 --- a/tools/cabana/.gitignore +++ b/tools/cabana/.gitignore @@ -1,5 +1,6 @@ moc_* *.moc +*.generated.qrc assets.cc diff --git a/tools/cabana/SConscript b/tools/cabana/SConscript index f5ef0f4393..04389a9ebf 100644 --- a/tools/cabana/SConscript +++ b/tools/cabana/SConscript @@ -2,6 +2,7 @@ import subprocess import os import shutil +import bootstrap_icons import libusb Import('env', 'arch', 'common', 'messaging', 'visionipc', 'cereal', 'replay_lib') @@ -80,10 +81,21 @@ if arch != "Darwin": opendbc_path = '-DOPENDBC_FILE_PATH=\'"%s"\'' % (cabana_env.Dir("../../opendbc/dbc").abspath) cabana_env['CXXFLAGS'] += [opendbc_path] +def write_assets_qrc(target, source, env): + with open(str(source[0])) as f: + qrc = f.read() + with open(str(target[0]), "w") as f: + f.write(qrc.replace("@BOOTSTRAP_ICONS_SVG@", str(bootstrap_icons.SVG_PATH))) + # build assets assets = "assets/assets.cc" -assets_src = "assets/assets.qrc" +assets_src = cabana_env.Command( + "assets/assets.generated.qrc", + "assets/assets.qrc", + write_assets_qrc, +) cabana_env.Command(assets, assets_src, f"rcc $SOURCES -o $TARGET") +cabana_env.Depends(assets_src, str(bootstrap_icons.SVG_PATH)) cabana_env.Depends(assets, Glob('/assets/*', exclude=[assets, assets_src, "assets/assets.o"])) cabana_srcs = ['mainwin.cc', 'streams/pandastream.cc', 'streams/devicestream.cc', 'streams/livestream.cc', 'streams/abstractstream.cc', 'streams/replaystream.cc', 'binaryview.cc', 'historylog.cc', 'videowidget.cc', 'signalview.cc', diff --git a/tools/cabana/assets/assets.qrc b/tools/cabana/assets/assets.qrc index 6a8e5a3414..f5880e5580 100644 --- a/tools/cabana/assets/assets.qrc +++ b/tools/cabana/assets/assets.qrc @@ -1,6 +1,6 @@ - ../../../third_party/bootstrap/bootstrap-icons.svg + @BOOTSTRAP_ICONS_SVG@ cabana-icon.png diff --git a/tools/cabana/binaryview.cc b/tools/cabana/binaryview.cc index 0be28f06b7..c86b3ebdae 100644 --- a/tools/cabana/binaryview.cc +++ b/tools/cabana/binaryview.cc @@ -40,14 +40,14 @@ BinaryView::BinaryView(QWidget *parent) : QTableView(parent) { addShortcuts(); setWhatsThis(R"( Binary View
- + Shortcuts
Delete Signal:  x ,  Backspace ,  Delete 
Change endianness:  e 
- Change singedness:  s 
+ Change signedness:  s 
Open chart:  c ,  p , diff --git a/tools/cabana/cabana b/tools/cabana/cabana index cd9bf1dd79..5eb15eabf0 100755 --- a/tools/cabana/cabana +++ b/tools/cabana/cabana @@ -33,6 +33,6 @@ fi # Build _cabana cd "$ROOT" -scons -j4 tools/cabana/_cabana cereal/messaging/bridge +scons tools/cabana/_cabana cereal/messaging/bridge exec "$DIR/_cabana" "$@" diff --git a/tools/cabana/messageswidget.cc b/tools/cabana/messageswidget.cc index ec8c82dd98..75cdaa7cc3 100644 --- a/tools/cabana/messageswidget.cc +++ b/tools/cabana/messageswidget.cc @@ -64,7 +64,7 @@ MessagesWidget::MessagesWidget(QWidget *parent) : menu(new QMenu(this)), QWidget setWhatsThis(tr(R"( Message View
- + Byte color
constant changing
increasing
@@ -146,7 +146,7 @@ void MessagesWidget::menuAboutToShow() { action->setCheckable(true); action->setChecked(settings.multiple_lines_hex); - action = menu->addAction(tr("Show inactive Messages"), model, &MessageListModel::showInactivemessages); + action = menu->addAction(tr("Show inactive messages"), model, &MessageListModel::showInactiveMessages); action->setCheckable(true); action->setChecked(model->show_inactive_messages); } @@ -216,7 +216,7 @@ void MessageListModel::setFilterStrings(const QMap &filters) { filterAndSort(); } -void MessageListModel::showInactivemessages(bool show) { +void MessageListModel::showInactiveMessages(bool show) { show_inactive_messages = show; filterAndSort(); } diff --git a/tools/cabana/messageswidget.h b/tools/cabana/messageswidget.h index 0fc09519a3..9ffb156604 100644 --- a/tools/cabana/messageswidget.h +++ b/tools/cabana/messageswidget.h @@ -36,7 +36,7 @@ public: int rowCount(const QModelIndex &parent = QModelIndex()) const override { return items_.size(); } void sort(int column, Qt::SortOrder order = Qt::AscendingOrder) override; void setFilterStrings(const QMap &filters); - void showInactivemessages(bool show); + void showInactiveMessages(bool show); void msgsReceived(const std::set *new_msgs, bool has_new_ids); bool filterAndSort(); void dbcModified(); diff --git a/tools/cabana/signalview.cc b/tools/cabana/signalview.cc index 15baabe512..a204512e83 100644 --- a/tools/cabana/signalview.cc +++ b/tools/cabana/signalview.cc @@ -495,7 +495,7 @@ SignalView::SignalView(ChartsWidget *charts, QWidget *parent) : charts(charts), setWhatsThis(tr(R"( Signal view
- + )")); } diff --git a/tools/cabana/videowidget.cc b/tools/cabana/videowidget.cc index f203ec663e..87d3cbec95 100644 --- a/tools/cabana/videowidget.cc +++ b/tools/cabana/videowidget.cc @@ -51,7 +51,7 @@ VideoWidget::VideoWidget(QWidget *parent) : QFrame(parent) { updatePlayBtnState(); setWhatsThis(tr(R"( Video
- + Timeline color diff --git a/tools/clip/run.py b/tools/clip/run.py index ed2a5075b4..d3a0496b1e 100755 --- a/tools/clip/run.py +++ b/tools/clip/run.py @@ -219,7 +219,7 @@ def load_route_metadata(route): params = Params() for entry in init_data.params.entries: try: - params.put(entry.key, params.cpp2python(entry.key, entry.value)) + params.put(entry.key, params.cpp2python(entry.key, entry.value), block=True) except UnknownKeyName: pass @@ -326,7 +326,7 @@ def clip(route: Route, output: str, start: int, end: int, headless: bool = True, frame_idx = 0 with tqdm.tqdm(total=len(message_chunks), desc="Rendering", unit="frame") as pbar: - for should_render in gui_app.render(): + for should_render, _, _ in gui_app.render(): if frame_idx >= len(message_chunks): break _, frame_bytes = frame_queue.get() diff --git a/tools/jotpluggler/.gitignore b/tools/jotpluggler/.gitignore index 7cb98300fe..5f5f9dbdec 100644 --- a/tools/jotpluggler/.gitignore +++ b/tools/jotpluggler/.gitignore @@ -3,6 +3,7 @@ jot_*.o *.o jotpluggler car_fingerprint_to_dbc.h +generated_event_extractors.h generated_dbcs/.stamp generated_dbcs/*.dbc layouts/.jotpluggler_autosave/ diff --git a/tools/jotpluggler/SConscript b/tools/jotpluggler/SConscript index 122d502341..078e173959 100644 --- a/tools/jotpluggler/SConscript +++ b/tools/jotpluggler/SConscript @@ -1,4 +1,6 @@ import os +import subprocess +import bootstrap_icons import imgui import libusb from opendbc import get_generated_dbcs @@ -15,6 +17,7 @@ jot_env["CPPPATH"] += [imgui.INCLUDE_DIR, libusb.INCLUDE_DIR] jot_env["CXXFLAGS"] += [ "-DGLFW_INCLUDE_NONE", '-DJOTP_REPO_ROOT=\'"%s"\'' % os.path.realpath(BASEDIR), + '-DBOOTSTRAP_ICONS_TTF=\'"%s"\'' % bootstrap_icons.TTF_PATH, ] def materialize_generated_dbcs(target, source, env): @@ -77,8 +80,24 @@ def write_car_fingerprint_to_dbc_header(target, source, env): return None +def generate_event_extractors(target, source, env): + subprocess.check_call([ + "python3", + "tools/jotpluggler/generate_event_extractors.py", + os.path.realpath(BASEDIR), + str(target[0]), + ]) + return None + generated_dbc_stamp = jot_env.Command(f"generated_dbcs/.stamp", [], materialize_generated_dbcs) car_fingerprint_to_dbc = jot_env.Command("car_fingerprint_to_dbc.h", [], write_car_fingerprint_to_dbc_header) +event_extractors = jot_env.Command("generated_event_extractors.h", [ + "generate_event_extractors.py", + jot_env.Glob("#cereal/*.capnp"), + jot_env.Glob("#cereal/include/*.capnp"), + ], + generate_event_extractors, +) libs = [replay_lib, common, messaging, visionipc, cereal, File(f"{imgui.LIB_DIR}/libimgui.a"), File(f"{imgui.LIB_DIR}/libglfw3.a"), "avformat", "avcodec", "avutil", "x264", "yuv", "z", "bz2", "zstd", "m", "pthread", "usb-1.0"] @@ -90,3 +109,4 @@ else: program = jot_env.Program("jotpluggler", jot_env.Glob("*.cc"), LIBS=libs) jot_env.Depends(program, generated_dbc_stamp) jot_env.Depends(program, car_fingerprint_to_dbc) +jot_env.Depends(program, event_extractors) diff --git a/tools/jotpluggler/app.cc b/tools/jotpluggler/app.cc index 4b56299ead..22a9f9021c 100644 --- a/tools/jotpluggler/app.cc +++ b/tools/jotpluggler/app.cc @@ -27,7 +27,7 @@ #include #include -#include "third_party/json11/json11.hpp" +#include "json11/json11.hpp" namespace fs = std::filesystem; @@ -324,7 +324,7 @@ void configure_style() { plot_style.LegendInnerPadding = ImVec2(6.0f, 3.0f); plot_style.LegendSpacing = ImVec2(7.0f, 2.0f); plot_style.PlotPadding = ImVec2(4.0f, 8.0f); - plot_style.FitPadding = ImVec2(0.02f, 0.4f); + plot_style.FitPadding = ImVec2(0.02f, static_cast(PLOT_Y_PADDING_FRACTION)); ImPlot::MapInputDefault(); ImPlotInputMap &input_map = ImPlot::GetInputMap(); @@ -1334,20 +1334,6 @@ bool apply_pane_menu_action(AppSession *session, UiState *state, int pane_index, layout_changed = true; success_status = "Plot view reset"; break; - case PaneMenuActionKind::ResetHorizontal: - reset_shared_range(state, *session); - state->follow_latest = session->data_mode == SessionDataMode::Stream; - state->suppress_range_side_effects = true; - clamp_shared_range(state, *session); - persist_shared_range_to_tab(tab, *state); - layout_changed = true; - success_status = "Horizontal zoom reset"; - break; - case PaneMenuActionKind::ResetVertical: - clear_pane_vertical_limits(&tab->panes[static_cast(pane_index)]); - layout_changed = true; - success_status = "Vertical zoom reset"; - break; case PaneMenuActionKind::Clear: clear_pane(tab, pane_index); tab_state->active_pane_index = pane_index; diff --git a/tools/jotpluggler/browser.cc b/tools/jotpluggler/browser.cc index 27378b4b6b..91e4a707da 100644 --- a/tools/jotpluggler/browser.cc +++ b/tools/jotpluggler/browser.cc @@ -377,20 +377,16 @@ void draw_browser_node(AppSession *session, } if (node.children.empty()) { - const bool selected = browser_selection_contains(*state, node.full_path); const std::string value_text = browser_series_value_text(*session, *state, node.full_path); const ImGuiStyle &style = ImGui::GetStyle(); const ImVec2 row_size(std::max(1.0f, ImGui::GetContentRegionAvail().x), ImGui::GetFrameHeight()); ImGui::PushID(node.full_path.c_str()); const bool clicked = ImGui::InvisibleButton("##browser_leaf", row_size); const bool hovered = ImGui::IsItemHovered(); - const bool held = ImGui::IsItemActive(); const ImRect rect(ImGui::GetItemRectMin(), ImGui::GetItemRectMax()); ImDrawList *draw_list = ImGui::GetWindowDrawList(); - if (selected || hovered) { - const ImU32 bg = ImGui::GetColorU32(selected - ? (held ? ImGuiCol_HeaderActive : ImGuiCol_Header) - : ImGuiCol_HeaderHovered); + if (hovered) { + const ImU32 bg = ImGui::GetColorU32(ImGuiCol_HeaderHovered); draw_list->AddRectFilled(rect.Min, rect.Max, bg, 0.0f); } @@ -409,7 +405,7 @@ void draw_browser_node(AppSession *session, nullptr); if (!value_text.empty()) { app_push_mono_font(); - ImGui::PushStyleColor(ImGuiCol_Text, selected ? color_rgb(70, 77, 86) : color_rgb(116, 124, 133)); + ImGui::PushStyleColor(ImGuiCol_Text, color_rgb(116, 124, 133)); ImGui::RenderTextClipped(ImVec2(value_left, rect.Min.y + style.FramePadding.y), ImVec2(value_right, rect.Max.y), value_text.c_str(), @@ -452,9 +448,6 @@ void draw_browser_node(AppSession *session, } ImGuiTreeNodeFlags flags = ImGuiTreeNodeFlags_SpanAvailWidth; - if (!filter.empty()) { - flags |= ImGuiTreeNodeFlags_DefaultOpen; - } const bool open = ImGui::TreeNodeEx(node.label.c_str(), flags); if (open) { for (const BrowserNode &child : node.children) { diff --git a/tools/jotpluggler/common.cc b/tools/jotpluggler/common.cc index 9bd6c18cea..8f696657bd 100644 --- a/tools/jotpluggler/common.cc +++ b/tools/jotpluggler/common.cc @@ -139,6 +139,14 @@ bool env_flag_enabled(const char *name, bool default_value) { return !(value == "0" || value == "false" || value == "no" || value == "off"); } +bool app_begin_popup(const char *str_id, ImGuiWindowFlags flags) { + return ImGui::BeginPopup(str_id, flags | ImGuiWindowFlags_NoMove); +} + +bool app_begin_popup_modal(const char *name, bool *p_open, ImGuiWindowFlags flags) { + return ImGui::BeginPopupModal(name, p_open, flags | ImGuiWindowFlags_NoMove); +} + void open_external_url(std::string_view url) { #ifdef __APPLE__ const std::string command = "open " + shell_quote(url) + " &"; diff --git a/tools/jotpluggler/common.h b/tools/jotpluggler/common.h index 25b1f91e89..14db83fd33 100644 --- a/tools/jotpluggler/common.h +++ b/tools/jotpluggler/common.h @@ -57,6 +57,10 @@ const char *stream_source_kind_label(StreamSourceKind kind); std::string stream_source_target_label(const StreamSourceConfig &source); bool env_flag_enabled(const char *name, bool default_value = false); +bool app_begin_popup(const char *str_id, ImGuiWindowFlags flags = 0); +bool app_begin_popup_modal(const char *name, + bool *p_open = nullptr, + ImGuiWindowFlags flags = ImGuiWindowFlags_AlwaysAutoResize); void open_external_url(std::string_view url); std::string route_useradmin_url(const RouteIdentifier &route_id); std::string route_connect_url(const RouteIdentifier &route_id); diff --git a/tools/jotpluggler/custom_series.cc b/tools/jotpluggler/custom_series.cc index bd2a3f36d1..aabf78a0db 100644 --- a/tools/jotpluggler/custom_series.cc +++ b/tools/jotpluggler/custom_series.cc @@ -11,7 +11,7 @@ #include #include -#include "third_party/json11/json11.hpp" +#include "json11/json11.hpp" namespace fs = std::filesystem; @@ -292,7 +292,7 @@ void draw_custom_series_help_popup(CustomSeriesEditorState *editor) { ImGui::OpenPopup("Custom Series Help"); editor->open_help = false; } - if (!ImGui::BeginPopupModal("Custom Series Help", nullptr, ImGuiWindowFlags_AlwaysAutoResize)) { + if (!app_begin_popup_modal("Custom Series Help")) { return; } ImGui::TextUnformatted("Available variables"); diff --git a/tools/jotpluggler/generate_event_extractors.py b/tools/jotpluggler/generate_event_extractors.py new file mode 100644 index 0000000000..1aba9578cd --- /dev/null +++ b/tools/jotpluggler/generate_event_extractors.py @@ -0,0 +1,327 @@ +import sys +import capnp +from pathlib import Path + +NO_DISCRIMINANT = 65535 +SCALAR_KINDS = { + "bool": "Bool", + "int8": "Int", + "int16": "Int", + "int32": "Int", + "int64": "Int", + "uint8": "UInt", + "uint16": "UInt", + "uint32": "UInt", + "uint64": "UInt", + "float32": "Float", + "float64": "Float", + "enum": "Enum", +} +NESTED_TYPE_KINDS = {"struct", "list"} +IGNORED_TYPE_KINDS = {"void", "text", "data", "interface", "anyPointer"} + + +def cxx_string(value): + return '"' + value.replace("\\", "\\\\").replace('"', '\\"') + '"' + + +def accessor(prefix, name): + return prefix + name[:1].upper() + name[1:] + + +def field_type(field): + if field.proto.which() == "group": + return "struct" + return field.proto.slot.type.which() + + +def field_type_proto(field): + return field.proto.slot.type if field.proto.which() == "slot" else None + + +def scalar_kind(type_proto): + if type_proto is None: + return None + return SCALAR_KINDS.get(type_proto.which()) + + +def enum_names(schema): + if schema is None: + return [] + names_by_ordinal = schema.enumerants + if not names_by_ordinal: + return [] + max_ordinal = max(names_by_ordinal.values()) + out = [""] * (max_ordinal + 1) + for name, ordinal in names_by_ordinal.items(): + out[ordinal] = name + return out + + +class Generator: + def __init__(self, event_schema): + self.event_schema = event_schema + self.fixed_paths = [] + self.tmp_index = 0 + self.lines = [] + self.emits_memo = {} + + def tmp(self, prefix): + self.tmp_index += 1 + return f"{prefix}_{self.tmp_index}" + + def add_fixed_path(self, path): + slot = len(self.fixed_paths) + self.fixed_paths.append(path) + return slot + + def emit(self, indent, text=""): + self.lines.append(" " * indent + text) + + def scalar_double_expr(self, value_expr, kind): + if kind == "Bool": + return f"({value_expr} ? 1.0 : 0.0)" + if kind == "Enum": + return f"static_cast(static_cast({value_expr}))" + return f"static_cast({value_expr})" + + def emit_enum_capture(self, indent, path_expr, names): + if not names: + return + names_expr = "{" + ", ".join(cxx_string(name) for name in names) + "}" + self.emit(indent, f"capture_static_enum_info({path_expr}, {names_expr}, series);") + + def emit_node(self, indent, type_kind, type_proto, schema, expr, path, path_expr, dynamic_path): + if not self.node_emits(type_kind, type_proto, schema): + return + kind = scalar_kind(type_proto) + if kind is not None: + double_expr = self.scalar_double_expr(expr, kind) + if dynamic_path: + if kind == "Enum": + self.emit_enum_capture(indent, path_expr, enum_names(schema)) + self.emit(indent, f"append_dynamic_scalar_point({path_expr}, tm, {double_expr}, series);") + else: + slot = self.add_fixed_path(path) + if kind == "Enum": + self.emit_enum_capture(indent, cxx_string(path), enum_names(schema)) + self.emit(indent, f"append_fixed_scalar_point(&series->fixed_series[{slot}], tm, {double_expr});") + return + + if type_kind == "struct": + self.emit_struct(indent, schema, expr, path, path_expr, dynamic_path) + return + + if type_kind == "list": + self.emit_list(indent, type_proto, schema, expr, path, path_expr, dynamic_path) + + def emit_field(self, indent, struct_schema, reader_expr, field_name, base_path, base_path_expr, dynamic_path): + field = struct_schema.fields[field_name] + proto = field.proto + type_kind = field_type(field) + type_proto = field_type_proto(field) + kind = scalar_kind(type_proto) + value_schema = field.schema if kind == "Enum" or type_kind in NESTED_TYPE_KINDS else None + if not self.node_emits(type_kind, type_proto, value_schema): + return + + field_path = f"{base_path}/{field_name}" + field_path_expr = None + if dynamic_path: + field_path_var = self.tmp("path") + self.emit(indent, f"const std::string {field_path_var} = {base_path_expr} + {cxx_string('/' + field_name)};") + field_path_expr = field_path_var + + get_call = f"{reader_expr}.{accessor('get', field_name)}()" + has_call = f"{reader_expr}.{accessor('has', field_name)}()" + conditions = [] + if proto.discriminantValue != NO_DISCRIMINANT: + conditions.append(f"{reader_expr}.which() == static_cast({proto.discriminantValue})") + if proto.which() == "slot" and type_kind in NESTED_TYPE_KINDS: + conditions.append(has_call) + + if conditions: + self.emit(indent, f"if ({' && '.join(conditions)}) {{") + indent += 2 + + value_var = self.tmp("value") + self.emit(indent, f"const auto {value_var} = {get_call};") + self.emit_node(indent, type_kind, type_proto, value_schema, value_var, field_path, field_path_expr, dynamic_path) + + if conditions: + indent -= 2 + self.emit(indent, "}") + + def emit_struct(self, indent, schema, reader_expr, path, path_expr, dynamic_path): + if schema is None: + return + for field_name in schema.fieldnames: + self.emit_field(indent, schema, reader_expr, field_name, path, path_expr, dynamic_path) + + def emit_list(self, indent, type_proto, schema, list_expr, path, path_expr, dynamic_path): + elem_type = type_proto.list.elementType + elem_kind = elem_type.which() + if elem_kind in IGNORED_TYPE_KINDS: + return + + base_path_var = path_expr + if base_path_var is None: + base_path_var = self.tmp("base_path") + self.emit(indent, f"const std::string {base_path_var} = {cxx_string(path)};") + + elem_scalar = scalar_kind(elem_type) + if elem_scalar is not None: + self.emit(indent, f"if ({list_expr}.size() <= 16) {{") + index_var = self.tmp("i") + self.emit(indent + 2, f"for (uint {index_var} = 0; {index_var} < {list_expr}.size(); ++{index_var}) {{") + item_series = self.tmp("item_series") + self.emit(indent + 4, f"RouteSeries *{item_series} = ensure_list_scalar_series({base_path_var}, {index_var}, series);") + if elem_scalar == "Enum": + self.emit_enum_capture(indent + 4, f"{item_series}->path", enum_names(schema.elementType)) + self.emit(indent + 4, f"append_fixed_scalar_point({item_series}, tm, {self.scalar_double_expr(f'{list_expr}[{index_var}]', elem_scalar)});") + self.emit(indent + 2, "}") + self.emit(indent, "}") + return + + if elem_kind in {"struct", "list"}: + index_var = self.tmp("i") + self.emit(indent, f"for (uint {index_var} = 0; {index_var} < {list_expr}.size(); ++{index_var}) {{") + item_path = self.tmp("item_path") + self.emit(indent + 2, f"const std::string {item_path} = {base_path_var} + \"/\" + std::to_string({index_var});") + item = self.tmp("item") + self.emit(indent + 2, f"const auto {item} = {list_expr}[{index_var}];") + if elem_kind == "struct": + self.emit_struct(indent + 2, schema.elementType, item, path, item_path, True) + else: + self.emit_list(indent + 2, elem_type, schema.elementType, item, path, item_path, True) + self.emit(indent, "}") + + def node_emits(self, type_kind, type_proto, schema, seen=frozenset()): + if scalar_kind(type_proto) is not None: + return True + if type_kind == "struct": + if schema is None: + return False + schema_id = int(schema.node.id) + if schema_id in seen: + return False + if schema_id in self.emits_memo: + return self.emits_memo[schema_id] + next_seen = seen | {schema_id} + for field_name in schema.fieldnames: + field = schema.fields[field_name] + ft = field_type(field) + ftp = field_type_proto(field) + fkind = scalar_kind(ftp) + if ft in IGNORED_TYPE_KINDS: + continue + fschema = field.schema if fkind == "Enum" or ft in NESTED_TYPE_KINDS else None + if self.node_emits(ft, ftp, fschema, next_seen): + self.emits_memo[schema_id] = True + return True + self.emits_memo[schema_id] = False + return False + if type_kind == "list": + if type_proto is None or schema is None: + return False + elem_type = type_proto.list.elementType + elem_kind = elem_type.which() + if elem_kind in IGNORED_TYPE_KINDS: + return False + if scalar_kind(elem_type) is not None: + return True + if elem_kind == "struct": + return self.node_emits("struct", None, schema.elementType, seen) + if elem_kind == "list": + return self.node_emits("list", elem_type, schema.elementType, seen) + return False + + def emit_can_special(self, indent, service_name): + service_kind = "CanServiceKind::Can" if service_name == "can" else "CanServiceKind::Sendcan" + self.emit(indent, f"const CanServiceKind can_service = {service_kind};") + self.emit(indent, f"for (const auto &msg : event.{accessor('get', service_name)}()) {{") + self.emit(indent + 2, "append_can_frame(can_service, static_cast(msg.getSrc()), msg.getAddress(), msg.getDeprecated().getBusTime(), msg.getDat(), tm, series);") # noqa: E501 + self.emit(indent + 2, "if (skip_raw_can) {") + self.emit(indent + 4, "const auto dat = msg.getDat();") + self.emit(indent + 4, f"decode_can_frame(can_dbc, {cxx_string(service_name)}, static_cast(msg.getSrc()), msg.getAddress(), dat.begin(), dat.size(), tm, series);") # noqa: E501 + self.emit(indent + 2, "}") + self.emit(indent, "}") + self.emit(indent, "if (skip_raw_can) {") + self.emit(indent + 2, "return true;") + self.emit(indent, "}") + + def emit_event_case(self, field_name): + field = self.event_schema.fields[field_name] + proto = field.proto + type_kind = field_type(field) + type_proto = field_type_proto(field) + kind = scalar_kind(type_proto) + schema = field.schema if kind == "Enum" or type_kind in NESTED_TYPE_KINDS else None + self.emit(4, f"case static_cast({proto.discriminantValue}): {{") + valid_slot = self.add_fixed_path(f"/{field_name}/valid") + mono_slot = self.add_fixed_path(f"/{field_name}/logMonoTime") + seconds_slot = self.add_fixed_path(f"/{field_name}/t") + self.emit(6, f"append_fixed_scalar_point(&series->fixed_series[{valid_slot}], tm, event.getValid() ? 1.0 : 0.0);") + self.emit(6, f"append_fixed_scalar_point(&series->fixed_series[{mono_slot}], tm, static_cast(event.getLogMonoTime()));") + self.emit(6, f"append_fixed_scalar_point(&series->fixed_series[{seconds_slot}], tm, tm);") + if field_name in {"can", "sendcan"}: + self.emit_can_special(6, field_name) + if self.node_emits(type_kind, type_proto, schema): + payload = self.tmp("payload") + self.emit(6, f"const auto {payload} = event.{accessor('get', field_name)}();") + self.emit_node(6, type_kind, type_proto, schema, payload, f"/{field_name}", None, False) + self.emit(6, "return true;") + self.emit(4, "}") + + def generate(self): + self.lines = [] + self.emit(0, "// Generated by tools/jotpluggler/generate_event_extractors.py; do not edit.") + self.emit(0, "") + self.emit(0, "const std::vector &static_event_fixed_paths() {") + self.emit(2, "static const std::vector paths = {") + path_insert_at = len(self.lines) + self.emit(2, "};") + self.emit(2, "return paths;") + self.emit(0, "}") + self.emit(0, "") + self.emit(0, "void capture_static_enum_info(const std::string &path, std::initializer_list names, SeriesAccumulator *series) {") + self.emit(2, "if (series->enum_info.find(path) != series->enum_info.end()) {") + self.emit(4, "return;") + self.emit(2, "}") + self.emit(2, "EnumInfo info;") + self.emit(2, "info.names.reserve(names.size());") + self.emit(2, "for (std::string_view name : names) {") + self.emit(4, "info.names.emplace_back(name);") + self.emit(2, "}") + self.emit(2, "if (!info.names.empty()) {") + self.emit(4, "series->enum_info.emplace(path, std::move(info));") + self.emit(2, "}") + self.emit(0, "}") + self.emit(0, "") + self.emit(0, "bool append_event_static_reader(cereal::Event::Which which, const cereal::Event::Reader &event, const dbc::Database *can_dbc, bool skip_raw_can, double time_offset, SeriesAccumulator *series) {") # noqa: E501 + self.emit(2, "const double tm = static_cast(event.getLogMonoTime()) / 1.0e9 - time_offset;") + self.emit(2, "switch (which) {") + for field_name in self.event_schema.union_fields: + self.emit_event_case(field_name) + self.emit(4, "default:") + self.emit(6, "return false;") + self.emit(2, "}") + self.emit(0, "}") + + path_lines = [" " + cxx_string(path) + "," for path in self.fixed_paths] + self.lines[path_insert_at:path_insert_at] = path_lines + return "\n".join(self.lines) + "\n" + + +if __name__ == "__main__": + if len(sys.argv) != 3: + print(f"usage: {sys.argv[0]} ", file=sys.stderr) + sys.exit(2) + + repo_root = Path(sys.argv[1]).resolve() + output = Path(sys.argv[2]) + capnp.remove_import_hook() + log = capnp.load(str(repo_root / "cereal" / "log.capnp")) + generated = Generator(log.Event.schema).generate() + output.parent.mkdir(parents=True, exist_ok=True) + output.write_text(generated) diff --git a/tools/jotpluggler/icons.cc b/tools/jotpluggler/icons.cc index 9507090e03..29edabad4e 100644 --- a/tools/jotpluggler/icons.cc +++ b/tools/jotpluggler/icons.cc @@ -4,7 +4,7 @@ #include void icon_add_font(float size, bool merge, const ImFont *base_font) { - const std::filesystem::path ttf = repo_root() / "third_party" / "bootstrap" / "bootstrap-icons.ttf"; + const std::filesystem::path ttf = BOOTSTRAP_ICONS_TTF; ImGuiIO &io = ImGui::GetIO(); ImFontConfig config; config.MergeMode = merge; diff --git a/tools/jotpluggler/internal.h b/tools/jotpluggler/internal.h index 22a5c1dd95..7b898f0461 100644 --- a/tools/jotpluggler/internal.h +++ b/tools/jotpluggler/internal.h @@ -26,8 +26,6 @@ enum class PaneMenuActionKind { SplitTop, SplitBottom, ResetView, - ResetHorizontal, - ResetVertical, Clear, Close, }; @@ -58,6 +56,7 @@ inline constexpr float SIDEBAR_MAX_WIDTH = 520.0f; inline constexpr float TIMELINE_BAR_HEIGHT = 14.0f; inline constexpr float STATUS_BAR_HEIGHT = 52.0f; inline constexpr double MIN_HORIZONTAL_ZOOM_SECONDS = 2.0; +inline constexpr double PLOT_Y_PADDING_FRACTION = 0.05; struct UiMetrics { float width = 0.0f; diff --git a/tools/jotpluggler/layout.cc b/tools/jotpluggler/layout.cc index 8a58ef7cd6..0d3b82c254 100644 --- a/tools/jotpluggler/layout.cc +++ b/tools/jotpluggler/layout.cc @@ -92,7 +92,7 @@ bool open_find_signal_result(UiState *state, const std::string &path) { } void draw_open_route_popup(AppSession *session, UiState *state) { - if (!ImGui::BeginPopupModal("Open Route", nullptr, ImGuiWindowFlags_AlwaysAutoResize)) { + if (!app_begin_popup_modal("Open Route")) { return; } ImGui::TextUnformatted("Load a route into the current layout."); @@ -116,7 +116,7 @@ void draw_open_route_popup(AppSession *session, UiState *state) { } void draw_stream_popup(AppSession *session, UiState *state) { - if (!ImGui::BeginPopupModal("Live Stream", nullptr, ImGuiWindowFlags_AlwaysAutoResize)) { + if (!app_begin_popup_modal("Live Stream")) { return; } @@ -153,7 +153,7 @@ void draw_stream_popup(AppSession *session, UiState *state) { } void draw_load_layout_popup(AppSession *session, UiState *state) { - if (!ImGui::BeginPopupModal("Load Layout", nullptr, ImGuiWindowFlags_AlwaysAutoResize)) { + if (!app_begin_popup_modal("Load Layout")) { return; } ImGui::TextUnformatted("Load a JotPlugger JSON layout."); @@ -177,7 +177,7 @@ void draw_load_layout_popup(AppSession *session, UiState *state) { } void draw_save_layout_popup(AppSession *session, UiState *state) { - if (!ImGui::BeginPopupModal("Save Layout", nullptr, ImGuiWindowFlags_AlwaysAutoResize)) { + if (!app_begin_popup_modal("Save Layout")) { return; } ImGui::TextUnformatted("Save the current workspace as a JotPlugger JSON layout."); @@ -201,7 +201,7 @@ void draw_save_layout_popup(AppSession *session, UiState *state) { } void draw_preferences_popup(AppSession *session, UiState *state) { - if (!ImGui::BeginPopupModal("Preferences", nullptr, ImGuiWindowFlags_AlwaysAutoResize)) { + if (!app_begin_popup_modal("Preferences")) { return; } if (session->map_data) { @@ -234,7 +234,7 @@ void draw_preferences_popup(AppSession *session, UiState *state) { } void draw_find_signal_popup(AppSession *session, UiState *state) { - if (!ImGui::BeginPopupModal("Find Signal", nullptr, ImGuiWindowFlags_AlwaysAutoResize)) { + if (!app_begin_popup_modal("Find Signal")) { return; } ImGui::TextUnformatted("Search decoded signals across the loaded route."); @@ -353,7 +353,7 @@ bool save_dbc_editor_contents(AppSession *session, UiState *state) { } void draw_dbc_editor_popup(AppSession *session, UiState *state) { - if (!ImGui::BeginPopupModal("DBC Editor", nullptr, ImGuiWindowFlags_AlwaysAutoResize)) { + if (!app_begin_popup_modal("DBC Editor")) { return; } DbcEditorState &editor = state->dbc_editor; @@ -392,7 +392,7 @@ void draw_dbc_editor_popup(AppSession *session, UiState *state) { } void draw_axis_limits_popup(AppSession *session, UiState *state) { - if (!ImGui::BeginPopupModal("Edit Axis Limits", nullptr, ImGuiWindowFlags_AlwaysAutoResize)) { + if (!app_begin_popup_modal("Edit Axis Limits")) { return; } const WorkspaceTab *tab = app_active_tab(session->layout, *state); @@ -452,7 +452,7 @@ void draw_error_popup(UiState *state) { ImGui::OpenPopup("Error"); state->open_error_popup = false; } - if (!ImGui::BeginPopupModal("Error", nullptr, ImGuiWindowFlags_AlwaysAutoResize)) { + if (!app_begin_popup_modal("Error")) { return; } ImGui::TextWrapped("%s", state->error_text.c_str()); diff --git a/tools/jotpluggler/layout_io.cc b/tools/jotpluggler/layout_io.cc index f984c0f0e8..5c70f7a42a 100644 --- a/tools/jotpluggler/layout_io.cc +++ b/tools/jotpluggler/layout_io.cc @@ -6,7 +6,7 @@ #include #include -#include "third_party/json11/json11.hpp" +#include "json11/json11.hpp" namespace fs = std::filesystem; diff --git a/tools/jotpluggler/layouts/driver-monitoring-debug.json b/tools/jotpluggler/layouts/driver-monitoring-debug.json new file mode 100644 index 0000000000..07a5c2fd6e --- /dev/null +++ b/tools/jotpluggler/layouts/driver-monitoring-debug.json @@ -0,0 +1 @@ +{"current_tab_index": 0, "tabs": [{"name": "tab1", "root": {"children": [{"children": [{"camera_view": "driver", "curves": [], "kind": "camera", "title": "Driver Camera"}, {"curves": [{"color": "#236bb4", "name": "/driverMonitoringState/alertLevel"}], "title": "..."}], "sizes": [0.5, 0.5], "split": "vertical"}, {"children": [{"curves": [{"color": "#236bb4", "name": "/driverMonitoringState/activePolicy"}], "title": "..."}, {"curves": [{"color": "#236bb4", "name": "/driverMonitoringState/visionPolicyState/faceDetected"}], "title": "..."}, {"curves": [{"color": "#236bb4", "name": "/driverMonitoringState/visionPolicyState/distractedTypes/eye"}, {"color": "#dc5234", "name": "/driverMonitoringState/visionPolicyState/distractedTypes/phone"}, {"color": "#43a047", "name": "/driverMonitoringState/visionPolicyState/distractedTypes/pose"}], "title": "..."}, {"curves": [{"color": "#236bb4", "name": "/driverMonitoringState/visionPolicyState/awarenessPercent"}], "title": "..."}], "sizes": [0.25, 0.25, 0.25, 0.25], "split": "vertical"}], "sizes": [0.5, 0.5], "split": "horizontal"}}]} diff --git a/tools/jotpluggler/map.cc b/tools/jotpluggler/map.cc index 8725908ea0..fb4e03c912 100644 --- a/tools/jotpluggler/map.cc +++ b/tools/jotpluggler/map.cc @@ -25,7 +25,7 @@ extern "C" { #include #include "common/util.h" -#include "third_party/json11/json11.hpp" +#include "json11/json11.hpp" namespace fs = std::filesystem; diff --git a/tools/jotpluggler/plot.cc b/tools/jotpluggler/plot.cc index 5d9d644808..019eff7070 100644 --- a/tools/jotpluggler/plot.cc +++ b/tools/jotpluggler/plot.cc @@ -7,8 +7,6 @@ #include #include -constexpr double PLOT_Y_PAD_FRACTION = 0.4; - struct PlotBounds { double x_min = 0.0; double x_max = 1.0; @@ -484,7 +482,7 @@ PlotBounds compute_plot_bounds(const Pane &pane, min_value = std::min(min_value, 0.0); max_value = std::max(max_value, 1.0); } - ensure_non_degenerate_range(&min_value, &max_value, PLOT_Y_PAD_FRACTION, 0.1); + ensure_non_degenerate_range(&min_value, &max_value, PLOT_Y_PADDING_FRACTION, 0.1); if (pane.range.has_y_limit_min) { min_value = pane.range.y_limit_min; } @@ -848,7 +846,7 @@ void draw_plot(const AppSession &session, Pane *pane, UiState *state) { } else { for (size_t i = 0; i < prepared_curves.size(); ++i) { const PreparedCurve &curve = prepared_curves[i]; - std::string series_id = curve_legend_label(curve, has_cursor_time, max_legend_label_width) + "##curve" + std::to_string(i); + std::string series_id = curve_legend_label(curve, has_cursor_time, max_legend_label_width) + "###curve" + std::to_string(curve.pane_curve_index); ImPlotSpec spec; spec.LineColor = color_rgb(curve.color); spec.LineWeight = curve.line_weight; @@ -923,28 +921,15 @@ std::optional draw_pane_context_menu(const WorkspaceTab &tab, in ImGui::Separator(); if (icon_menu_item(icon::ZOOM_OUT, "Zoom Out", nullptr, false, is_plot)) { action.kind = PaneMenuActionKind::ResetView; - } else if (icon_menu_item(icon::ARROW_LEFT_RIGHT, "Zoom Out Horizontally", nullptr, false, is_plot)) { - action.kind = PaneMenuActionKind::ResetHorizontal; - } else if (icon_menu_item(icon::ARROW_DOWN_UP, "Zoom Out Vertically", nullptr, false, is_plot)) { - action.kind = PaneMenuActionKind::ResetVertical; } ImGui::Separator(); if (icon_menu_item(icon::TRASH, "Remove ALL curves", nullptr, false, is_plot)) { action.kind = PaneMenuActionKind::Clear; } ImGui::Separator(); - icon_menu_item(icon::ARROW_LEFT_RIGHT, "Flip Horizontal Axis", nullptr, false, false); - icon_menu_item(icon::ARROW_DOWN_UP, "Flip Vertical Axis", nullptr, false, false); - ImGui::Separator(); - icon_menu_item(icon::FILES, "Copy", nullptr, false, false); - icon_menu_item(icon::CLIPBOARD2, "Paste", nullptr, false, false); icon_menu_item(icon::FILE_EARMARK_IMAGE, "Copy image to clipboard", nullptr, false, false); icon_menu_item(icon::SAVE, "Save plot to file", nullptr, false, false); icon_menu_item(icon::BAR_CHART, "Show data statistics", nullptr, false, false); - ImGui::Separator(); - if (icon_menu_item(icon::X_SQUARE, "Close Pane")) { - action.kind = PaneMenuActionKind::Close; - } ImGui::EndPopup(); if (action.kind == PaneMenuActionKind::None) return std::nullopt; return action; diff --git a/tools/jotpluggler/runtime.cc b/tools/jotpluggler/runtime.cc index 6eb2be80e8..3247a5d01d 100644 --- a/tools/jotpluggler/runtime.cc +++ b/tools/jotpluggler/runtime.cc @@ -71,7 +71,6 @@ bool should_subscribe_stream_service(const std::string &name) { "livestreamRoadEncodeIdx", "livestreamDriverEncodeIdx", "thumbnail", - "navThumbnail", }}; if (name == "rawAudioData") return false; for (std::string_view skipped : kSkippedServices) { diff --git a/tools/jotpluggler/session.cc b/tools/jotpluggler/session.cc index 173df7bc04..beb0a292be 100644 --- a/tools/jotpluggler/session.cc +++ b/tools/jotpluggler/session.cc @@ -444,8 +444,7 @@ void draw_route_info_popup(AppSession *session, UiState *state, ImVec2 anchor) { } ImGui::SetNextWindowPos(anchor, ImGuiCond_Appearing); ImGui::SetNextWindowSizeConstraints(ImVec2(300.0f, 0.0f), ImVec2(420.0f, FLT_MAX)); - if (!ImGui::BeginPopup("##route_info_popup", - ImGuiWindowFlags_NoMove | ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings)) { + if (!app_begin_popup("##route_info_popup", ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings)) { return; } @@ -643,7 +642,7 @@ void draw_route_id_chip(AppSession *session, UiState *state) { } ImGui::SetNextWindowPos(ImVec2(chip_max.x - 60.0f, chip_max.y + 4.0f), ImGuiCond_Appearing); - if (ImGui::BeginPopup("##route_selector_popup")) { + if (app_begin_popup("##route_selector_popup")) { for (LogSelector selector : {LogSelector::Auto, LogSelector::RLog, LogSelector::QLog}) { const bool selected = route_id.selector == selector; const std::string label = std::string(log_selector_name(selector)) + " " + log_selector_description(selector); diff --git a/tools/jotpluggler/sketch_layout.cc b/tools/jotpluggler/sketch_layout.cc index d9622dde6d..2091280169 100644 --- a/tools/jotpluggler/sketch_layout.cc +++ b/tools/jotpluggler/sketch_layout.cc @@ -2,7 +2,6 @@ #include "tools/jotpluggler/car_fingerprint_to_dbc.h" #include "tools/jotpluggler/common.h" -#include #include #include @@ -10,6 +9,7 @@ #include #include #include +#include #include #include #include @@ -23,7 +23,7 @@ #include #include "common/util.h" -#include "third_party/json11/json11.hpp" +#include "json11/json11.hpp" #include "tools/replay/logreader.h" #include "tools/replay/py_downloader.h" @@ -51,47 +51,7 @@ struct SegmentLogs { std::string qcamera; }; -enum class ScalarKind { - None, - Bool, - Int, - UInt, - Float, - Enum, -}; - -enum class ResolvedNodeKind { - Ignore, - Scalar, - Struct, - List, -}; - -struct ResolvedNode { - ResolvedNodeKind kind = ResolvedNodeKind::Ignore; - ScalarKind scalar_kind = ScalarKind::None; - int fixed_slot = -1; - bool has_field = false; - capnp::StructSchema::Field field; - std::string segment; - std::string path; - bool skip_large_scalar_list = false; - std::vector children; - std::unique_ptr element; -}; - -struct ResolvedService { - uint16_t event_which = 0; - capnp::StructSchema::Field union_field; - std::string service_name; - int valid_slot = -1; - int log_mono_time_slot = -1; - int seconds_slot = -1; - ResolvedNode payload; -}; - struct SchemaIndex { - std::vector> by_which; size_t fixed_series_count = 0; std::vector fixed_paths; @@ -112,6 +72,27 @@ struct SeriesAccumulator { std::unordered_map enum_info; }; +void append_fixed_scalar_point(RouteSeries *series, double tm, double value); +void append_dynamic_scalar_point(const std::string &path, double tm, double value, SeriesAccumulator *series); +RouteSeries *ensure_list_scalar_series(const std::string &base_path, size_t index, SeriesAccumulator *series); +void append_can_frame(CanServiceKind service, + uint8_t bus, + uint32_t address, + uint16_t bus_time, + capnp::Data::Reader dat, + double tm, + SeriesAccumulator *series); +void decode_can_frame(const dbc::Database *can_dbc, + const std::string &service_name, + uint8_t bus, + uint32_t address, + const uint8_t *raw, + size_t data_size, + double tm, + SeriesAccumulator *series); + +#include "tools/jotpluggler/generated_event_extractors.h" + struct LoadedRouteArtifacts { std::vector series; std::vector can_messages; @@ -898,125 +879,11 @@ SketchLayout parse_layout(const fs::path &layout_path) { return layout; } -ScalarKind scalar_kind_for_type(const capnp::Type &type) { - if (type.isBool()) return ScalarKind::Bool; - if (type.isInt8() || type.isInt16() || type.isInt32() || type.isInt64()) { - return ScalarKind::Int; - } - if (type.isUInt8() || type.isUInt16() || type.isUInt32() || type.isUInt64()) { - return ScalarKind::UInt; - } - if (type.isFloat32() || type.isFloat64()) { - return ScalarKind::Float; - } - if (type.isEnum()) return ScalarKind::Enum; - return ScalarKind::None; -} - -ResolvedNode build_resolved_type(const capnp::Type &type, - bool has_field, - capnp::StructSchema::Field field, - std::string segment, - std::string path, - size_t *next_fixed_slot, - std::vector *fixed_paths, - bool dynamic_path = false) { - ResolvedNode node; - node.has_field = has_field; - node.field = field; - node.segment = std::move(segment); - node.path = std::move(path); - node.scalar_kind = scalar_kind_for_type(type); - if (node.scalar_kind != ScalarKind::None) { - node.kind = ResolvedNodeKind::Scalar; - if (!dynamic_path) { - node.fixed_slot = static_cast((*next_fixed_slot)++); - fixed_paths->push_back(node.path); - } - return node; - } - - if (type.isStruct()) { - node.kind = ResolvedNodeKind::Struct; - for (auto child : type.asStruct().getFields()) { - const std::string child_segment = child.getProto().getName().cStr(); - node.children.push_back(build_resolved_type( - child.getType(), - true, - child, - child_segment, - node.path + "/" + child_segment, - next_fixed_slot, - fixed_paths, - dynamic_path)); - } - return node; - } - - if (type.isList()) { - const capnp::Type element_type = type.asList().getElementType(); - if (element_type.isText() || element_type.isData() || element_type.isInterface() || element_type.isAnyPointer()) { - node.kind = ResolvedNodeKind::Ignore; - return node; - } - node.kind = ResolvedNodeKind::List; - node.skip_large_scalar_list = scalar_kind_for_type(element_type) != ScalarKind::None; - node.element = std::make_unique( - build_resolved_type(element_type, - false, - capnp::StructSchema::Field(), - "", - node.path, - next_fixed_slot, - fixed_paths, - true)); - return node; - } - - node.kind = ResolvedNodeKind::Ignore; - return node; -} - -int register_fixed_series_path(const std::string &path, - size_t *next_fixed_slot, - std::vector *fixed_paths) { - const int slot = static_cast((*next_fixed_slot)++); - fixed_paths->push_back(path); - return slot; -} - const SchemaIndex &SchemaIndex::instance() { static const SchemaIndex index = [] { SchemaIndex out; - const auto event_schema = capnp::Schema::from().asStruct(); - uint16_t max_discriminant = 0; - for (auto union_field : event_schema.getUnionFields()) { - max_discriminant = std::max(max_discriminant, union_field.getProto().getDiscriminantValue()); - } - out.by_which.resize(static_cast(max_discriminant) + 1); - size_t next_fixed_slot = 0; - for (auto union_field : event_schema.getUnionFields()) { - ResolvedService service; - service.event_which = union_field.getProto().getDiscriminantValue(); - service.union_field = union_field; - service.service_name = union_field.getProto().getName().cStr(); - service.valid_slot = register_fixed_series_path( - "/" + service.service_name + "/valid", &next_fixed_slot, &out.fixed_paths); - service.log_mono_time_slot = register_fixed_series_path( - "/" + service.service_name + "/logMonoTime", &next_fixed_slot, &out.fixed_paths); - service.seconds_slot = register_fixed_series_path( - "/" + service.service_name + "/t", &next_fixed_slot, &out.fixed_paths); - service.payload = build_resolved_type( - union_field.getType(), - false, - capnp::StructSchema::Field(), - service.service_name, - "/" + service.service_name, - &next_fixed_slot, - &out.fixed_paths); - out.by_which[service.event_which] = std::move(service); - } - out.fixed_series_count = next_fixed_slot; + out.fixed_paths = static_event_fixed_paths(); + out.fixed_series_count = out.fixed_paths.size(); return out; }(); return index; @@ -1026,45 +893,6 @@ bool is_absolute_curve(const std::string &name) { return !name.empty() && name.front() == '/'; } -std::optional scalar_value_to_double(const capnp::DynamicValue::Reader &value, ScalarKind kind) { - switch (kind) { - case ScalarKind::Bool: - return value.as() ? 1.0 : 0.0; - case ScalarKind::Int: - return static_cast(value.as()); - case ScalarKind::UInt: - return static_cast(value.as()); - case ScalarKind::Float: - return value.as(); - case ScalarKind::Enum: - return static_cast(value.as().getRaw()); - case ScalarKind::None: - return std::nullopt; - } - return std::nullopt; -} - -void capture_enum_info(const std::string &path, - const capnp::DynamicValue::Reader &value, - SeriesAccumulator *series) { - if (series->enum_info.find(path) != series->enum_info.end()) { - return; - } - - const auto dynamic_enum = value.as(); - EnumInfo info; - for (auto enumerant : dynamic_enum.getSchema().getEnumerants()) { - const uint16_t ordinal = enumerant.getOrdinal(); - if (ordinal >= info.names.size()) { - info.names.resize(static_cast(ordinal) + 1); - } - info.names[ordinal] = enumerant.getProto().getName().cStr(); - } - if (!info.names.empty()) { - series->enum_info.emplace(path, std::move(info)); - } -} - void append_scalar_point(RouteSeries *series, const std::string &path, double tm, @@ -1195,156 +1023,9 @@ void append_dynamic_scalar_point(const std::string &path, double tm, double valu append_scalar_point(ensure_dynamic_series(path, series), path, tm, value); } -void append_scalar_value(const ResolvedNode &node, - const std::string *path_override, - const capnp::DynamicValue::Reader &raw_value, - double tm, - double value, - SeriesAccumulator *series) { - if (path_override == nullptr && node.fixed_slot >= 0) { - if (node.scalar_kind == ScalarKind::Enum) { - capture_enum_info(node.path, raw_value, series); - } - append_fixed_scalar_point(&series->fixed_series[static_cast(node.fixed_slot)], tm, value); - return; - } - - const std::string &path = path_override != nullptr ? *path_override : node.path; - if (node.scalar_kind == ScalarKind::Enum) { - capture_enum_info(path, raw_value, series); - } - append_dynamic_scalar_point(path, tm, value, series); -} - -void append_fast_node(const ResolvedNode &node, - const capnp::DynamicValue::Reader &value, - double tm, - SeriesAccumulator *series, - const std::string *path_override = nullptr) { - switch (node.kind) { - case ResolvedNodeKind::Scalar: { - if (std::optional scalar = scalar_value_to_double(value, node.scalar_kind); scalar.has_value()) { - append_scalar_value(node, path_override, value, tm, *scalar, series); - } - return; - } - case ResolvedNodeKind::Struct: { - const capnp::DynamicStruct::Reader reader = value.as(); - for (const ResolvedNode &child : node.children) { - if (!child.has_field || !reader.has(child.field)) continue; - if (path_override == nullptr) { - append_fast_node(child, reader.get(child.field), tm, series, nullptr); - } else { - const std::string child_path = child.segment.empty() ? *path_override : (*path_override + "/" + child.segment); - append_fast_node(child, reader.get(child.field), tm, series, &child_path); - } - } - return; - } - case ResolvedNodeKind::List: { - if (!node.element) { - return; - } - const capnp::DynamicList::Reader list = value.as(); - if (list.size() == 0) { - return; - } - if (node.skip_large_scalar_list && list.size() > 16) { - return; - } - const std::string &base_path = path_override != nullptr ? *path_override : node.path; - if (node.element->kind == ResolvedNodeKind::Scalar) { - for (uint i = 0; i < list.size(); ++i) { - if (std::optional scalar = scalar_value_to_double(list[i], node.element->scalar_kind); scalar.has_value()) { - RouteSeries *item_series = ensure_list_scalar_series(base_path, i, series); - if (node.element->scalar_kind == ScalarKind::Enum && !item_series->path.empty()) { - capture_enum_info(item_series->path, list[i], series); - } - append_fixed_scalar_point(item_series, tm, *scalar); - } - } - return; - } - for (uint i = 0; i < list.size(); ++i) { - const std::string item_path = base_path + "/" + std::to_string(i); - append_fast_node(*node.element, list[i], tm, series, &item_path); - } - return; - } - case ResolvedNodeKind::Ignore: - return; - } -} - -void append_event_fast_reader(cereal::Event::Which which, - const cereal::Event::Reader &event, - const SchemaIndex &schema, - const dbc::Database *can_dbc, - bool skip_raw_can, - double time_offset, - SeriesAccumulator *series) { - const uint16_t which_index = static_cast(which); - if (which_index >= schema.by_which.size() || !schema.by_which[which_index].has_value()) { - return; - } - const ResolvedService &service = *schema.by_which[which_index]; - const capnp::DynamicStruct::Reader dynamic_event(event); - const capnp::DynamicValue::Reader payload = dynamic_event.get(service.union_field); - const double tm = static_cast(event.getLogMonoTime()) / 1.0e9 - time_offset; - append_fixed_scalar_point(&series->fixed_series[static_cast(service.valid_slot)], - tm, - event.getValid() ? 1.0 : 0.0); - append_fixed_scalar_point(&series->fixed_series[static_cast(service.log_mono_time_slot)], - tm, - static_cast(event.getLogMonoTime())); - append_fixed_scalar_point(&series->fixed_series[static_cast(service.seconds_slot)], - tm, - tm); - if (service.service_name == "can" || service.service_name == "sendcan") { - const CanServiceKind can_service = service.service_name == "can" - ? CanServiceKind::Can - : CanServiceKind::Sendcan; - auto decode_message = [&](uint8_t bus, uint32_t address, const auto &dat_reader) { - const auto bytes = dat_reader.begin(); - decode_can_frame(can_dbc, service.service_name, bus, address, bytes, dat_reader.size(), tm, series); - }; - if (service.service_name == "can") { - for (const auto &msg : event.getCan()) { - append_can_frame(can_service, - static_cast(msg.getSrc()), - msg.getAddress(), - msg.getDeprecated().getBusTime(), - msg.getDat(), - tm, - series); - if (!skip_raw_can) continue; - decode_message(static_cast(msg.getSrc()), msg.getAddress(), msg.getDat()); - } - } else { - for (const auto &msg : event.getSendcan()) { - append_can_frame(can_service, - static_cast(msg.getSrc()), - msg.getAddress(), - msg.getDeprecated().getBusTime(), - msg.getDat(), - tm, - series); - if (!skip_raw_can) continue; - decode_message(static_cast(msg.getSrc()), msg.getAddress(), msg.getDat()); - } - } - if (skip_raw_can) { - return; - } - } - - append_fast_node(service.payload, payload, tm, series); -} - void append_event_fast(cereal::Event::Which which, int32_t eidx_segnum, kj::ArrayPtr data, - const SchemaIndex &schema, const dbc::Database *can_dbc, bool skip_raw_can, double time_offset, @@ -1353,14 +1034,13 @@ void append_event_fast(cereal::Event::Which which, return; } with_parseable_event(data, [&](const cereal::Event::Reader &event) { - append_event_fast_reader(which, event, schema, can_dbc, skip_raw_can, time_offset, series); + append_event_static_reader(which, event, can_dbc, skip_raw_can, time_offset, series); }); } void append_events_fast_range(const std::vector &events, size_t begin, size_t end, - const SchemaIndex &schema, const dbc::Database *can_dbc, bool skip_raw_can, SeriesAccumulator *series) { @@ -1369,7 +1049,6 @@ void append_events_fast_range(const std::vector &events, append_event_fast(event_record.which, event_record.eidx_segnum, event_record.data, - schema, can_dbc, skip_raw_can, 0.0, @@ -1802,7 +1481,7 @@ SeriesAccumulator extract_segment_series(const std::vector &events, const size_t chunk_count = extract_chunk_count(events.size(), worker_budget, segment_workers); if (chunk_count <= 1 || events.empty()) { SeriesAccumulator series = make_series_accumulator(schema); - append_events_fast_range(events, 0, events.size(), schema, can_dbc, skip_raw_can, &series); + append_events_fast_range(events, 0, events.size(), can_dbc, skip_raw_can, &series); return series; } @@ -1819,10 +1498,10 @@ SeriesAccumulator extract_segment_series(const std::vector &events, workers.emplace_back([&, chunk]() { const size_t begin = chunk * events_per_chunk; const size_t end = std::min(events.size(), begin + events_per_chunk); - append_events_fast_range(events, begin, end, schema, can_dbc, skip_raw_can, &chunk_results[chunk]); + append_events_fast_range(events, begin, end, can_dbc, skip_raw_can, &chunk_results[chunk]); }); } - append_events_fast_range(events, 0, std::min(events.size(), events_per_chunk), schema, can_dbc, skip_raw_can, &chunk_results[0]); + append_events_fast_range(events, 0, std::min(events.size(), events_per_chunk), can_dbc, skip_raw_can, &chunk_results[0]); for (std::thread &worker : workers) { worker.join(); } @@ -2044,13 +1723,12 @@ void StreamAccumulator::appendEvent(kj::ArrayPtr data) { } } - append_event_fast_reader(which, - event, - impl_->schema, - impl_->can_dbc ? &*impl_->can_dbc : nullptr, - impl_->can_dbc.has_value(), - *impl_->time_offset, - &impl_->series); + append_event_static_reader(which, + event, + impl_->can_dbc ? &*impl_->can_dbc : nullptr, + impl_->can_dbc.has_value(), + *impl_->time_offset, + &impl_->series); append_log_event(which, event, *impl_->time_offset, &impl_->logs, &impl_->last_alert_key); if (which == cereal::Event::Which::SELFDRIVE_STATE) { const auto sd = event.getSelfdriveState(); diff --git a/tools/joystick/joystick_control.py b/tools/joystick/joystick_control.py index 11d17e587e..b1f14043b7 100755 --- a/tools/joystick/joystick_control.py +++ b/tools/joystick/joystick_control.py @@ -110,7 +110,7 @@ def send_thread(joystick): def joystick_control_thread(joystick): - Params().put_bool('JoystickDebugMode', True) + Params().put_bool('JoystickDebugMode', True, block=True) threading.Thread(target=send_thread, args=(joystick,), daemon=True).start() while True: joystick.update() diff --git a/tools/lateral_maneuvers/lateral_maneuversd.py b/tools/lateral_maneuvers/lateral_maneuversd.py index d8a7185410..4f68d9be08 100755 --- a/tools/lateral_maneuvers/lateral_maneuversd.py +++ b/tools/lateral_maneuvers/lateral_maneuversd.py @@ -13,7 +13,7 @@ from openpilot.tools.longitudinal_maneuvers.maneuversd import Action, Maneuver a # thresholds for starting maneuvers MAX_SPEED_DEV = 0.7 # deviation in m/s MAX_CURV = 0.002 # 500 m radius -MAX_ROLL = 0.08 # 4.56° +MAX_ROLL = 0.12 # 6.8° TIMER = 2.0 # sec stable conditions before starting maneuver @dataclass diff --git a/tools/op.sh b/tools/op.sh index dccf080829..538d689569 100755 --- a/tools/op.sh +++ b/tools/op.sh @@ -21,8 +21,14 @@ if [ "$(uname)" == "Darwin" ] && [ $SHELL == "/bin/bash" ]; then fi function op_install() { echo "Installing op system-wide..." - CMD="\nalias op='"$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )/op.sh" \"\$@\"'\n" - grep "alias op=" "$RC_FILE" &> /dev/null || printf "$CMD" >> $RC_FILE + OP_SH="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )/op.sh" + CMD=$(cat </dev/null || printf '\n%s\n' "$CMD" >> "$RC_FILE" echo -e " ↳ [${GREEN}✔${NC}] op installed successfully. Open a new shell to use it." } diff --git a/tools/plotjuggler/juggle.py b/tools/plotjuggler/juggle.py index c86945ef6b..a31c62c940 100755 --- a/tools/plotjuggler/juggle.py +++ b/tools/plotjuggler/juggle.py @@ -29,6 +29,18 @@ MINIMUM_PLOTJUGGLER_VERSION = (3, 5, 2) MAX_STREAMING_BUFFER_SIZE = 1000 +def print_jotpluggler_banner(): + purple = "\033[95m" if sys.stdout.isatty() else "" + reset = "\033[0m" if purple else "" + print(f"{purple}+-------------------------------------------------------------+{reset}") + print(f"{purple}|{reset} JotPluggler is the future! Try it like this: {purple}|{reset}") + print(f"{purple}|{reset} ./tools/jotpluggler/jotpluggler --demo --layout tuning {purple}|{reset}") + print(f"{purple}|{reset} {purple}|{reset}") + print(f"{purple}|{reset} PlotJuggler will be deleted soon. {purple}|{reset}") + print(f"{purple}|{reset} Missing a feature? Open an issue or post in #dev-openpilot. {purple}|{reset}") + print(f"{purple}+-------------------------------------------------------------+{reset}") + + def install(): m = f"{platform.system()}-{platform.machine()}" supported = ("Linux-x86_64", "Linux-aarch64", "Darwin-arm64") @@ -118,10 +130,15 @@ if __name__ == "__main__": parser.add_argument("route_or_segment_name", nargs='?', help="The route or segment name to plot (cabana share URL accepted)") if len(sys.argv) == 1: + print_jotpluggler_banner() + print() parser.print_help() sys.exit() args = parser.parse_args() + print_jotpluggler_banner() + print() + if args.install: install() sys.exit() diff --git a/tools/replay/py_downloader.cc b/tools/replay/py_downloader.cc index 5063d6947c..d27a77e6ee 100644 --- a/tools/replay/py_downloader.cc +++ b/tools/replay/py_downloader.cc @@ -5,6 +5,7 @@ #include #include #include +#include #include "tools/replay/util.h" @@ -13,9 +14,9 @@ namespace { static std::mutex handler_mutex; static DownloadProgressHandler progress_handler = nullptr; -// Run a Python command and capture stdout. Optionally parse stderr for PROGRESS lines. +// Run a Python command and capture stdout. Stderr is left attached to the parent. // Returns stdout content. If abort is signaled, kills the child process. -std::string runPython(const std::vector &args, std::atomic *abort = nullptr, bool parse_progress = false) { +std::string runPython(const std::vector &args, std::atomic *abort = nullptr) { // Build argv for execvp std::vector argv; argv.push_back("python3"); @@ -27,22 +28,15 @@ std::string runPython(const std::vector &args, std::atomic *a argv.push_back(nullptr); int stdout_pipe[2]; - int stderr_pipe[2]; if (pipe(stdout_pipe) != 0) { rWarning("py_downloader: pipe() failed"); return {}; } - if (pipe(stderr_pipe) != 0) { - rWarning("py_downloader: pipe() failed"); - close(stdout_pipe[0]); close(stdout_pipe[1]); - return {}; - } pid_t pid = fork(); if (pid < 0) { rWarning("py_downloader: fork() failed"); close(stdout_pipe[0]); close(stdout_pipe[1]); - close(stderr_pipe[0]); close(stderr_pipe[1]); return {}; } @@ -61,11 +55,8 @@ std::string runPython(const std::vector &args, std::atomic *a unsetenv("OPENPILOT_PREFIX"); close(stdout_pipe[0]); - close(stderr_pipe[0]); dup2(stdout_pipe[1], STDOUT_FILENO); - dup2(stderr_pipe[1], STDERR_FILENO); close(stdout_pipe[1]); - close(stderr_pipe[1]); execvp("python3", const_cast(argv.data())); _exit(127); @@ -73,32 +64,28 @@ std::string runPython(const std::vector &args, std::atomic *a // Parent process close(stdout_pipe[1]); - close(stderr_pipe[1]); std::string stdout_data; - std::string stderr_buf; char buf[4096]; - // Use select() to read from both pipes + // Use select() so abort can interrupt while waiting for Python output. fd_set rfds; - int max_fd = std::max(stdout_pipe[0], stderr_pipe[0]); - bool stdout_open = true, stderr_open = true; + bool stdout_open = true; - while (stdout_open || stderr_open) { + while (stdout_open) { if (abort && *abort) { kill(pid, SIGTERM); break; } FD_ZERO(&rfds); - if (stdout_open) FD_SET(stdout_pipe[0], &rfds); - if (stderr_open) FD_SET(stderr_pipe[0], &rfds); + FD_SET(stdout_pipe[0], &rfds); struct timeval tv = {0, 100000}; // 100ms timeout - int ret = select(max_fd + 1, &rfds, nullptr, nullptr, &tv); + int ret = select(stdout_pipe[0] + 1, &rfds, nullptr, nullptr, &tv); if (ret < 0) break; - if (stdout_open && FD_ISSET(stdout_pipe[0], &rfds)) { + if (FD_ISSET(stdout_pipe[0], &rfds)) { ssize_t n = read(stdout_pipe[0], buf, sizeof(buf)); if (n <= 0) { stdout_open = false; @@ -106,45 +93,15 @@ std::string runPython(const std::vector &args, std::atomic *a stdout_data.append(buf, n); } } - - if (stderr_open && FD_ISSET(stderr_pipe[0], &rfds)) { - ssize_t n = read(stderr_pipe[0], buf, sizeof(buf)); - if (n <= 0) { - stderr_open = false; - } else { - stderr_buf.append(buf, n); - // Parse complete lines from stderr - size_t pos; - while ((pos = stderr_buf.find('\n')) != std::string::npos) { - std::string line = stderr_buf.substr(0, pos); - stderr_buf.erase(0, pos + 1); - - if (parse_progress && line.rfind("PROGRESS:", 0) == 0) { - // Parse "PROGRESS::" - auto colon1 = line.find(':', 9); - if (colon1 != std::string::npos) { - try { - uint64_t cur = std::stoull(line.c_str() + 9); - uint64_t total = std::stoull(line.c_str() + colon1 + 1); - std::lock_guard lk(handler_mutex); - if (progress_handler) { - progress_handler(cur, total, true); - } - } catch (...) {} - } - } else if (line.rfind("ERROR:", 0) == 0) { - rWarning("py_downloader: %s", line.c_str() + 6); - } - } - } - } } // Drain remaining pipe data to prevent child from blocking on write - for (int fd : {stdout_pipe[0], stderr_pipe[0]}) { - while (read(fd, buf, sizeof(buf)) > 0) {} - close(fd); + while (true) { + ssize_t n = read(stdout_pipe[0], buf, sizeof(buf)); + if (n <= 0) break; + stdout_data.append(buf, n); } + close(stdout_pipe[0]); int status; waitpid(pid, &status, 0); @@ -192,7 +149,7 @@ std::string download(const std::string &url, bool use_cache, std::atomic * if (!use_cache) { args.push_back("--no-cache"); } - return runPython(args, abort, true); + return runPython(args, abort); } std::string getRouteFiles(const std::string &route) { diff --git a/tools/replay/qcom_decoder.cc b/tools/replay/qcom_decoder.cc index 44ff16ce4f..b7f04a063b 100644 --- a/tools/replay/qcom_decoder.cc +++ b/tools/replay/qcom_decoder.cc @@ -1,7 +1,7 @@ #include "qcom_decoder.h" #include -#include "third_party/linux/include/v4l2-controls.h" +#include #include @@ -343,4 +343,4 @@ bool MsmVidc::handleEvent() { break; } return true; -} \ No newline at end of file +} diff --git a/tools/replay/route.cc b/tools/replay/route.cc index e7b8ed6bba..df4fa813cf 100644 --- a/tools/replay/route.cc +++ b/tools/replay/route.cc @@ -4,7 +4,7 @@ #include #include -#include "third_party/json11/json11.hpp" +#include "json11/json11.hpp" #include "system/hardware/hw.h" #include "tools/replay/py_downloader.h" #include "tools/replay/replay.h" diff --git a/tools/replay/route.h b/tools/replay/route.h index 119a81152e..50f3eba854 100644 --- a/tools/replay/route.h +++ b/tools/replay/route.h @@ -8,7 +8,7 @@ #include #include -#include "third_party/json11/json11.hpp" +#include "json11/json11.hpp" #include "tools/replay/framereader.h" #include "tools/replay/logreader.h" #include "tools/replay/util.h" diff --git a/tools/scripts/devsync.py b/tools/scripts/devsync.py new file mode 100755 index 0000000000..98312dd545 --- /dev/null +++ b/tools/scripts/devsync.py @@ -0,0 +1,93 @@ +#!/usr/bin/env python3 +import argparse +import shlex +import subprocess +import threading +import time + +from watchdog.events import FileSystemEventHandler +from watchdog.observers import Observer + +from openpilot.common.basedir import BASEDIR + + +def build_rsync_cmd(args) -> list[str]: + ssh = [ + "ssh", + "-o", "ControlMaster=auto", + "-o", f"ControlPath=/tmp/devsync-{args.ip}.ctl", + "-o", "ControlPersist=10m", + "-o", "StrictHostKeyChecking=accept-new", + ] + if args.identity: + ssh += ["-i", args.identity] + + return [ + "rsync", "-az", + "--files-from=-", "--from0", + "-e", " ".join(shlex.quote(p) for p in ssh), + "--out-format=%n", + BASEDIR + "/", f"comma@{args.ip}:{args.remote}/", + ] + + +def git_tracked_files() -> bytes: + return subprocess.check_output( + ["git", "-C", BASEDIR, "ls-files", "--recurse-submodules", "-z"] + ) + + +class Handler(FileSystemEventHandler): + def __init__(self, sync_fn): + self.dirty = threading.Event() + self.sync_fn = sync_fn + + def on_any_event(self, event): + if not event.is_directory: + self.dirty.set() + + def run(self): + while True: + time.sleep(1) + if self.dirty.is_set(): + self.dirty.clear() + self.sync_fn() + + +def main(): + p = argparse.ArgumentParser() + p.add_argument("ip", help="device IP / hostname") + p.add_argument("--remote", default="/data/openpilot", help="remote path on device") + p.add_argument("-i", "--identity", default=None, help="ssh identity file") + args = p.parse_args() + + print(f"[devsync] watching {BASEDIR}") + print(f"[devsync] target comma@{args.ip}:{args.remote}") + + def run_sync(): + file_list = git_tracked_files() + cmd = build_rsync_cmd(args) + t0 = time.monotonic() + r = subprocess.run(cmd, input=file_list, capture_output=True) + dt = time.monotonic() - t0 + if r.returncode: + print(f"[devsync] ERR rc={r.returncode} in {dt:.2f}s") + return + files = [ln for ln in r.stdout.decode().splitlines() if ln.strip()] + msg = f"{len(files)} files: {', '.join(files)}" if files else "no changes" + print(f"[devsync] {dt:.2f}s · {msg}") + + run_sync() + + handler = Handler(run_sync) + obs = Observer() + obs.schedule(handler, BASEDIR, recursive=True) + obs.start() + handler.run() + + +if __name__ == "__main__": + try: + main() + except KeyboardInterrupt: + print("\n[devsync] stopping") diff --git a/tools/scripts/setup_ssh_keys.py b/tools/scripts/setup_ssh_keys.py index 45dc0aa977..e599dd3c5d 100755 --- a/tools/scripts/setup_ssh_keys.py +++ b/tools/scripts/setup_ssh_keys.py @@ -15,9 +15,9 @@ if __name__ == "__main__": if keys.status_code == 200: params = Params() - params.put_bool("SshEnabled", True) - params.put("GithubSshKeys", keys.text) - params.put("GithubUsername", username) + params.put_bool("SshEnabled", True, block=True) + params.put("GithubSshKeys", keys.text, block=True) + params.put("GithubUsername", username, block=True) print("Set up ssh keys successfully") else: print("Error getting public keys from github") diff --git a/tools/setup_dependencies.sh b/tools/setup_dependencies.sh index 8132cd16dc..6cfd75ce17 100755 --- a/tools/setup_dependencies.sh +++ b/tools/setup_dependencies.sh @@ -19,7 +19,7 @@ function retry() { return 1 } -function install_ubuntu_deps() { +function install_linux_deps() { SUDO="" if [[ ! $(id -u) -eq 0 ]]; then @@ -30,61 +30,60 @@ function install_ubuntu_deps() { SUDO="sudo" fi - # Detect OS using /etc/os-release file - if [ -f "/etc/os-release" ]; then - source /etc/os-release - case "$VERSION_CODENAME" in - "jammy" | "kinetic" | "noble") - ;; - *) - echo "$ID $VERSION_ID is unsupported. This setup script is written for Ubuntu 24.04." - read -p "Would you like to attempt installation anyway? " -n 1 -r - echo "" - if [[ ! $REPLY =~ ^[Yy]$ ]]; then - exit 1 - fi - ;; - esac + local missing_linux_deps=0 + for cmd in gcc g++ make curl curl-config git; do + if ! command -v "$cmd" > /dev/null 2>&1; then + missing_linux_deps=1 + break + fi + done + + # normal stuff, this mostly for bare docker images + if [[ "$missing_linux_deps" -eq 0 ]]; then + # the native package managers are slow, so skip if we can + echo "[ ] system packages already installed t=$SECONDS" + elif command -v apt-get > /dev/null 2>&1; then + $SUDO apt-get update + $SUDO apt-get install -y --no-install-recommends ca-certificates build-essential curl libcurl4-openssl-dev locales git + elif command -v dnf > /dev/null 2>&1; then + $SUDO dnf install -y ca-certificates gcc gcc-c++ make curl libcurl-devel glibc-langpack-en git + elif command -v yum > /dev/null 2>&1; then + $SUDO yum install -y ca-certificates gcc gcc-c++ make curl libcurl-devel glibc-langpack-en git + elif command -v pacman > /dev/null 2>&1; then + $SUDO pacman -Syu --noconfirm --needed base-devel ca-certificates curl git + elif command -v zypper > /dev/null 2>&1; then + $SUDO zypper --non-interactive refresh + $SUDO zypper --non-interactive install ca-certificates gcc gcc-c++ make curl libcurl-devel glibc-locale git + elif command -v apk > /dev/null 2>&1; then + $SUDO apk add --no-cache ca-certificates build-base curl curl-dev musl-locales git + elif command -v xbps-install > /dev/null 2>&1; then + $SUDO xbps-install -Syu base-devel ca-certificates curl git libcurl-devel glibc-locales else - echo "No /etc/os-release in the system. Make sure you're running on Ubuntu, or similar." + echo "Unsupported Linux distribution. Supported package managers: apt-get, dnf, yum, pacman, zypper, apk, xbps-install." exit 1 fi - $SUDO apt-get update - - # normal stuff, mostly for the bare docker image - $SUDO apt-get install -y --no-install-recommends \ - ca-certificates \ - build-essential \ - curl \ - libcurl4-openssl-dev \ - locales \ - git \ - xvfb - if [[ -d "/etc/udev/rules.d/" ]]; then - # Setup jungle udev rules - $SUDO tee /etc/udev/rules.d/12-panda_jungle.rules > /dev/null < /dev/null <<-EOF + # Panda Jungle devices + SUBSYSTEM=="usb", ATTRS{idVendor}=="3801", ATTRS{idProduct}=="ddcf", MODE="0666" + SUBSYSTEM=="usb", ATTRS{idVendor}=="3801", ATTRS{idProduct}=="ddef", MODE="0666" + SUBSYSTEM=="usb", ATTRS{idVendor}=="bbaa", ATTRS{idProduct}=="ddcf", MODE="0666" + SUBSYSTEM=="usb", ATTRS{idVendor}=="bbaa", ATTRS{idProduct}=="ddef", MODE="0666" -EOF + # Panda devices + SUBSYSTEM=="usb", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="df11", MODE="0666" + SUBSYSTEM=="usb", ATTRS{idVendor}=="3801", ATTRS{idProduct}=="ddcc", MODE="0666" + SUBSYSTEM=="usb", ATTRS{idVendor}=="3801", ATTRS{idProduct}=="ddee", MODE="0666" + SUBSYSTEM=="usb", ATTRS{idVendor}=="bbaa", ATTRS{idProduct}=="ddcc", MODE="0666" + SUBSYSTEM=="usb", ATTRS{idVendor}=="bbaa", ATTRS{idProduct}=="ddee", MODE="0666" - # Setup panda udev rules - $SUDO tee /etc/udev/rules.d/11-panda.rules > /dev/null < /dev/null <
Disengaged